├── .gitee ├── ISSUE_TEMPLATE.zh-CN.md └── PULL_REQUEST_TEMPLATE.zh-CN.md ├── .gitignore ├── Code Project ├── BlueSkyFlightControl.ioc ├── CMakeLists.txt ├── CMakeLists_template.txt ├── Core │ ├── Inc │ │ ├── FreeRTOSConfig.h │ │ ├── adc.h │ │ ├── dma.h │ │ ├── gpio.h │ │ ├── i2c.h │ │ ├── main.h │ │ ├── sdmmc.h │ │ ├── spi.h │ │ ├── stm32h7xx_hal_conf.h │ │ ├── stm32h7xx_it.h │ │ ├── tim.h │ │ └── usart.h │ ├── Src │ │ ├── adc.c │ │ ├── dma.c │ │ ├── freertos.c │ │ ├── gpio.c │ │ ├── i2c.c │ │ ├── main.c │ │ ├── sdmmc.c │ │ ├── spi.c │ │ ├── stm32h7xx_hal_msp.c │ │ ├── stm32h7xx_hal_timebase_tim.c │ │ ├── stm32h7xx_it.c │ │ ├── syscalls.c │ │ ├── sysmem.c │ │ ├── system_stm32h7xx.c │ │ ├── tim.c │ │ └── usart.c │ └── Startup │ │ └── startup_stm32h743vitx.s ├── Drivers │ ├── CMSIS │ │ ├── Device │ │ │ └── ST │ │ │ │ └── STM32H7xx │ │ │ │ └── Include │ │ │ │ ├── stm32h743xx.h │ │ │ │ ├── stm32h7xx.h │ │ │ │ └── system_stm32h7xx.h │ │ └── Include │ │ │ ├── cmsis_armcc.h │ │ │ ├── cmsis_armclang.h │ │ │ ├── cmsis_compiler.h │ │ │ ├── cmsis_gcc.h │ │ │ ├── cmsis_iccarm.h │ │ │ ├── cmsis_version.h │ │ │ ├── core_armv8mbl.h │ │ │ ├── core_armv8mml.h │ │ │ ├── core_cm0.h │ │ │ ├── core_cm0plus.h │ │ │ ├── core_cm1.h │ │ │ ├── core_cm23.h │ │ │ ├── core_cm3.h │ │ │ ├── core_cm33.h │ │ │ ├── core_cm4.h │ │ │ ├── core_cm7.h │ │ │ ├── core_sc000.h │ │ │ ├── core_sc300.h │ │ │ ├── mpu_armv7.h │ │ │ ├── mpu_armv8.h │ │ │ └── tz_context.h │ └── STM32H7xx_HAL_Driver │ │ ├── Inc │ │ ├── Legacy │ │ │ └── stm32_hal_legacy.h │ │ ├── stm32h7xx_hal.h │ │ ├── stm32h7xx_hal_adc.h │ │ ├── stm32h7xx_hal_adc_ex.h │ │ ├── stm32h7xx_hal_cortex.h │ │ ├── stm32h7xx_hal_def.h │ │ ├── stm32h7xx_hal_dma.h │ │ ├── stm32h7xx_hal_dma_ex.h │ │ ├── stm32h7xx_hal_exti.h │ │ ├── stm32h7xx_hal_flash.h │ │ ├── stm32h7xx_hal_flash_ex.h │ │ ├── stm32h7xx_hal_gpio.h │ │ ├── stm32h7xx_hal_gpio_ex.h │ │ ├── stm32h7xx_hal_hsem.h │ │ ├── stm32h7xx_hal_i2c.h │ │ ├── stm32h7xx_hal_i2c_ex.h │ │ ├── stm32h7xx_hal_mdma.h │ │ ├── stm32h7xx_hal_pcd.h │ │ ├── stm32h7xx_hal_pcd_ex.h │ │ ├── stm32h7xx_hal_pwr.h │ │ ├── stm32h7xx_hal_pwr_ex.h │ │ ├── stm32h7xx_hal_rcc.h │ │ ├── stm32h7xx_hal_rcc_ex.h │ │ ├── stm32h7xx_hal_sd.h │ │ ├── stm32h7xx_hal_sd_ex.h │ │ ├── stm32h7xx_hal_spi.h │ │ ├── stm32h7xx_hal_spi_ex.h │ │ ├── stm32h7xx_hal_tim.h │ │ ├── stm32h7xx_hal_tim_ex.h │ │ ├── stm32h7xx_hal_uart.h │ │ ├── stm32h7xx_hal_uart_ex.h │ │ ├── stm32h7xx_ll_adc.h │ │ ├── stm32h7xx_ll_delayblock.h │ │ ├── stm32h7xx_ll_sdmmc.h │ │ └── stm32h7xx_ll_usb.h │ │ └── Src │ │ ├── stm32h7xx_hal.c │ │ ├── stm32h7xx_hal_adc.c │ │ ├── stm32h7xx_hal_adc_ex.c │ │ ├── stm32h7xx_hal_cortex.c │ │ ├── stm32h7xx_hal_dma.c │ │ ├── stm32h7xx_hal_dma_ex.c │ │ ├── stm32h7xx_hal_exti.c │ │ ├── stm32h7xx_hal_flash.c │ │ ├── stm32h7xx_hal_flash_ex.c │ │ ├── stm32h7xx_hal_gpio.c │ │ ├── stm32h7xx_hal_hsem.c │ │ ├── stm32h7xx_hal_i2c.c │ │ ├── stm32h7xx_hal_i2c_ex.c │ │ ├── stm32h7xx_hal_mdma.c │ │ ├── stm32h7xx_hal_pcd.c │ │ ├── stm32h7xx_hal_pcd_ex.c │ │ ├── stm32h7xx_hal_pwr.c │ │ ├── stm32h7xx_hal_pwr_ex.c │ │ ├── stm32h7xx_hal_rcc.c │ │ ├── stm32h7xx_hal_rcc_ex.c │ │ ├── stm32h7xx_hal_sd.c │ │ ├── stm32h7xx_hal_sd_ex.c │ │ ├── stm32h7xx_hal_spi.c │ │ ├── stm32h7xx_hal_spi_ex.c │ │ ├── stm32h7xx_hal_tim.c │ │ ├── stm32h7xx_hal_tim_ex.c │ │ ├── stm32h7xx_hal_uart.c │ │ ├── stm32h7xx_hal_uart_ex.c │ │ ├── stm32h7xx_ll_delayblock.c │ │ ├── stm32h7xx_ll_sdmmc.c │ │ └── stm32h7xx_ll_usb.c ├── FATFS │ ├── App │ │ ├── fatfs.c │ │ └── fatfs.h │ └── Target │ │ ├── bsp_driver_sd.c │ │ ├── bsp_driver_sd.h │ │ ├── fatfs_platform.c │ │ ├── fatfs_platform.h │ │ ├── ffconf.h │ │ ├── sd_diskio.c │ │ └── sd_diskio.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_high_latency2.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 │ ├── message_definitions │ │ └── v1.0 │ │ │ └── common.xml │ └── protocol.h ├── 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 │ │ │ ├── ff.c │ │ │ ├── ff.h │ │ │ ├── ff_gen_drv.c │ │ │ ├── ff_gen_drv.h │ │ │ ├── integer.h │ │ │ └── option │ │ │ ├── cc936.c │ │ │ └── syscall.c │ │ └── FreeRTOS │ │ └── Source │ │ ├── CMSIS_RTOS_V2 │ │ ├── cmsis_os.h │ │ ├── cmsis_os2.c │ │ └── cmsis_os2.h │ │ ├── croutine.c │ │ ├── event_groups.c │ │ ├── include │ │ ├── FreeRTOS.h │ │ ├── StackMacros.h │ │ ├── croutine.h │ │ ├── deprecated_definitions.h │ │ ├── event_groups.h │ │ ├── list.h │ │ ├── message_buffer.h │ │ ├── mpu_prototypes.h │ │ ├── mpu_wrappers.h │ │ ├── portable.h │ │ ├── projdefs.h │ │ ├── queue.h │ │ ├── semphr.h │ │ ├── stack_macros.h │ │ ├── stream_buffer.h │ │ ├── task.h │ │ └── timers.h │ │ ├── list.c │ │ ├── portable │ │ ├── GCC │ │ │ └── ARM_CM4F │ │ │ │ ├── port.c │ │ │ │ └── portmacro.h │ │ └── MemMang │ │ │ └── heap_4.c │ │ ├── queue.c │ │ ├── stream_buffer.c │ │ ├── tasks.c │ │ └── timers.c ├── SRC │ ├── CONTROL │ │ ├── commandControl.c │ │ ├── commandControl.h │ │ ├── flightControl.c │ │ ├── flightControl.h │ │ ├── missionControl.c │ │ ├── missionControl.h │ │ ├── motor.c │ │ ├── motor.h │ │ ├── rc.c │ │ ├── rc.h │ │ ├── safeControl.c │ │ ├── safeControl.h │ │ ├── userControl.c │ │ ├── userControl.h │ │ ├── waypointControl.c │ │ └── waypointControl.h │ ├── DRIVER │ │ ├── board.c │ │ ├── board.h │ │ ├── boardConfigBlueSkyV3.h │ │ ├── drv_adc.c │ │ ├── drv_adc.h │ │ ├── drv_flash.c │ │ ├── drv_flash.h │ │ ├── drv_i2c.c │ │ ├── drv_i2c.h │ │ ├── drv_i2c_soft.c │ │ ├── drv_i2c_soft.h │ │ ├── drv_ibus.c │ │ ├── drv_ibus.h │ │ ├── drv_pwm.c │ │ ├── drv_pwm.h │ │ ├── drv_sbus.c │ │ ├── drv_sbus.h │ │ ├── drv_spi.c │ │ ├── drv_spi.h │ │ ├── drv_uart.c │ │ ├── drv_uart.h │ │ ├── drv_usb.c │ │ └── drv_usb.h │ ├── LOG │ │ ├── logger.c │ │ ├── logger.h │ │ ├── ulog.c │ │ ├── ulog.h │ │ ├── ulog_data.c │ │ └── ulog_data.h │ ├── MATH │ │ ├── LevenbergMarquardt.c │ │ ├── LevenbergMarquardt.h │ │ ├── declination.c │ │ ├── declination.h │ │ ├── kalman3.c │ │ ├── kalman3.h │ │ ├── kalmanVel.c │ │ ├── kalmanVel.h │ │ ├── lowPassFilter.c │ │ ├── lowPassFilter.h │ │ ├── mathTool.c │ │ ├── mathTool.h │ │ ├── matrix3.c │ │ ├── matrix3.h │ │ ├── matrix6.c │ │ ├── matrix6.h │ │ ├── pid.c │ │ ├── pid.h │ │ ├── quaternion.c │ │ ├── quaternion.h │ │ ├── rotation.c │ │ ├── rotation.h │ │ ├── vector3.c │ │ └── vector3.h │ ├── MESSAGE │ │ ├── bsklink.c │ │ ├── bsklink.h │ │ ├── bsklinkDecode.c │ │ ├── bsklinkDecode.h │ │ ├── bsklinkSend.c │ │ ├── bsklinkSend.h │ │ ├── mavlinkDecode.c │ │ ├── mavlinkDecode.h │ │ ├── mavlinkNotice.c │ │ ├── mavlinkNotice.h │ │ ├── mavlinkParam.c │ │ ├── mavlinkParam.h │ │ ├── mavlinkSend.c │ │ ├── mavlinkSend.h │ │ ├── message.c │ │ └── message.h │ ├── MODULE │ │ ├── LC302.c │ │ ├── LC302.h │ │ ├── PX4FLOW.c │ │ ├── PX4FLOW.h │ │ ├── Servo.c │ │ ├── Servo.h │ │ ├── battery.c │ │ ├── battery.h │ │ ├── buzzer.c │ │ ├── buzzer.h │ │ ├── icm20602.c │ │ ├── icm20602.h │ │ ├── icm20689.c │ │ ├── icm20689.h │ │ ├── icm20948.c │ │ ├── icm20948.h │ │ ├── ist8310.c │ │ ├── ist8310.h │ │ ├── module.c │ │ ├── module.h │ │ ├── mpu6500.c │ │ ├── mpu6500.h │ │ ├── ms5611.c │ │ ├── ms5611.h │ │ ├── rgb.c │ │ ├── rgb.h │ │ ├── spl06-001.c │ │ ├── spl06-001.h │ │ ├── spl06-007.c │ │ ├── spl06-007.h │ │ ├── tfminiplus.c │ │ ├── tfminiplus.h │ │ ├── ublox.c │ │ └── ublox.h │ ├── NAVIGATION │ │ ├── ahrs.c │ │ ├── ahrs.h │ │ ├── ahrsAux.c │ │ ├── ahrsAux.h │ │ ├── navigation.c │ │ └── navigation.h │ ├── SENSOR │ │ ├── ToFaltimeter.c │ │ ├── ToFaltimeter.h │ │ ├── accelerometer.c │ │ ├── accelerometer.h │ │ ├── barometer.c │ │ ├── barometer.h │ │ ├── gps.c │ │ ├── gps.h │ │ ├── gyroscope.c │ │ ├── gyroscope.h │ │ ├── magnetometer.c │ │ ├── magnetometer.h │ │ ├── optflow.c │ │ ├── optflow.h │ │ ├── sensor.c │ │ └── sensor.h │ ├── SYSTEM │ │ ├── faultDetect.c │ │ ├── faultDetect.h │ │ ├── flightStatus.c │ │ ├── flightStatus.h │ │ ├── parameter.c │ │ └── parameter.h │ └── TASK │ │ ├── TaskConfig.h │ │ ├── control_task.c │ │ ├── control_task.h │ │ ├── log_task.c │ │ ├── log_task.h │ │ ├── messageQueue.c │ │ ├── messageQueue.h │ │ ├── message_task.c │ │ ├── message_task.h │ │ ├── module_task.c │ │ ├── module_task.h │ │ ├── navigation_task.c │ │ ├── navigation_task.h │ │ ├── sensor_task.c │ │ └── sensor_task.h ├── STM32H743VITX_FLASH.ld ├── STM32H743VITX_RAM.ld └── USB_DEVICE │ ├── App │ ├── usb_device.c │ ├── usb_device.h │ ├── usbd_cdc_if.c │ ├── usbd_cdc_if.h │ ├── usbd_desc.c │ └── usbd_desc.h │ └── Target │ ├── usbd_conf.c │ └── usbd_conf.h ├── LICENSE ├── Object Task ├── README.md ├── mission_line.py ├── pid.py ├── protocol.py ├── protocol_demo.py ├── test_camera.py ├── test_math.py ├── test_serial.py └── vision.py ├── README.md ├── 天穹飞控代码分析.md ├── 飞控任务和控制任务流程图.png ├── 飞控全局变量和静态变量.md ├── 飞行任务状态图.png └── 飞行状态更新(原天穹代码).png /.gitee/ISSUE_TEMPLATE.zh-CN.md: -------------------------------------------------------------------------------- 1 | ### 该问题是怎么引起的? 2 | 3 | 4 | 5 | ### 重现步骤 6 | 7 | 8 | 9 | ### 报错信息 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /.gitee/PULL_REQUEST_TEMPLATE.zh-CN.md: -------------------------------------------------------------------------------- 1 | ### 相关的Issue 2 | 3 | 4 | ### 原因(目的、解决的问题等) 5 | 6 | 7 | ### 描述(做了什么,变更了什么) 8 | 9 | 10 | ### 测试用例(新增、改动、可能影响的功能) 11 | 12 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # Prerequisites 2 | *.d 3 | 4 | # Object files 5 | *.o 6 | *.ko 7 | *.obj 8 | *.elf 9 | 10 | # Linker output 11 | *.ilk 12 | *.map 13 | *.exp 14 | 15 | # Precompiled Headers 16 | *.gch 17 | *.pch 18 | 19 | # Libraries 20 | *.lib 21 | *.a 22 | *.la 23 | *.lo 24 | 25 | # Shared objects (inc. Windows DLLs) 26 | *.dll 27 | *.so 28 | *.so.* 29 | *.dylib 30 | 31 | # Executables 32 | *.exe 33 | *.out 34 | *.app 35 | *.i*86 36 | *.x86_64 37 | *.hex 38 | 39 | # Debug files 40 | *.dSYM/ 41 | *.su 42 | *.idb 43 | *.pdb 44 | 45 | # Kernel Module Compile Results 46 | *.mod* 47 | *.cmd 48 | .tmp_versions/ 49 | modules.order 50 | Module.symvers 51 | Mkfile.old 52 | dkms.conf 53 | -------------------------------------------------------------------------------- /Code Project/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | #THIS FILE IS AUTO GENERATED FROM THE TEMPLATE! DO NOT CHANGE! 2 | set(CMAKE_SYSTEM_NAME Generic) 3 | set(CMAKE_SYSTEM_VERSION 1) 4 | cmake_minimum_required(VERSION 3.19) 5 | 6 | # specify cross compilers and tools 7 | set(CMAKE_C_COMPILER arm-none-eabi-gcc) 8 | set(CMAKE_CXX_COMPILER arm-none-eabi-g++) 9 | set(CMAKE_ASM_COMPILER arm-none-eabi-gcc) 10 | set(CMAKE_AR arm-none-eabi-ar) 11 | set(CMAKE_OBJCOPY arm-none-eabi-objcopy) 12 | set(CMAKE_OBJDUMP arm-none-eabi-objdump) 13 | set(SIZE arm-none-eabi-size) 14 | set(CMAKE_TRY_COMPILE_TARGET_TYPE STATIC_LIBRARY) 15 | 16 | # project settings 17 | project(BlueSkyFlightControl C CXX ASM) 18 | set(CMAKE_CXX_STANDARD 17) 19 | set(CMAKE_C_STANDARD 11) 20 | 21 | #Uncomment for hardware floating point 22 | add_compile_definitions(ARM_MATH_CM7;ARM_MATH_MATRIX_CHECK;ARM_MATH_ROUNDING) 23 | add_compile_options(-mfloat-abi=hard -mfpu=fpv5-d16) 24 | add_link_options(-mfloat-abi=hard -mfpu=fpv5-d16) 25 | 26 | #Uncomment for software floating point 27 | #add_compile_options(-mfloat-abi=soft) 28 | 29 | add_compile_options(-mcpu=cortex-m7 -mthumb -mthumb-interwork) 30 | add_compile_options(-ffunction-sections -fdata-sections -fno-common -fmessage-length=0) 31 | 32 | # uncomment to mitigate c++17 absolute addresses warnings 33 | #set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-register") 34 | 35 | if ("${CMAKE_BUILD_TYPE}" STREQUAL "Release") 36 | message(STATUS "Maximum optimization for speed") 37 | add_compile_options(-Ofast) 38 | elseif ("${CMAKE_BUILD_TYPE}" STREQUAL "RelWithDebInfo") 39 | message(STATUS "Maximum optimization for speed, debug info included") 40 | add_compile_options(-Ofast -g) 41 | elseif ("${CMAKE_BUILD_TYPE}" STREQUAL "MinSizeRel") 42 | message(STATUS "Maximum optimization for size") 43 | add_compile_options(-Os) 44 | else () 45 | message(STATUS "Minimal optimization, debug info included") 46 | add_compile_options(-Og -g) 47 | endif () 48 | 49 | include_directories(Core/Inc FATFS/Target FATFS/App USB_DEVICE/App USB_DEVICE/Target Drivers/STM32H7xx_HAL_Driver/Inc Drivers/STM32H7xx_HAL_Driver/Inc/Legacy Middlewares/Third_Party/FreeRTOS/Source/include Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2 Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F Middlewares/Third_Party/FatFs/src Middlewares/ST/STM32_USB_Device_Library/Core/Inc Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc Drivers/CMSIS/Device/ST/STM32H7xx/Include Drivers/CMSIS/Include 50 | SRC/DRIVER 51 | SRC/MATH 52 | SRC/MODULE 53 | SRC/CONTROL 54 | SRC/NAVIGATION 55 | SRC/SYSTEM 56 | SRC/SENSOR 57 | SRC/MESSAGE 58 | SRC/LOG 59 | SRC/TASK 60 | 61 | MAVLINK/ 62 | MAVLINK/common) 63 | 64 | add_definitions(-DUSE_HAL_DRIVER -DSTM32H743xx -DDEBUG) 65 | 66 | file(GLOB_RECURSE SOURCES "Core/*.*" "FATFS/*.*" "Middlewares/*.*" "Drivers/*.*" "USB_DEVICE/*.*" 67 | "SRC/*.*" "MAVLINK/*.*") 68 | 69 | set(LINKER_SCRIPT ${CMAKE_SOURCE_DIR}/STM32H743VITX_FLASH.ld) 70 | 71 | add_link_options(-Wl,-gc-sections,--print-memory-usage,-Map=${PROJECT_BINARY_DIR}/${PROJECT_NAME}.map) 72 | add_link_options(-mcpu=cortex-m7 -mthumb -mthumb-interwork) 73 | add_link_options(-T ${LINKER_SCRIPT}) 74 | 75 | add_executable(${PROJECT_NAME}.elf ${SOURCES} ${LINKER_SCRIPT}) 76 | 77 | set(HEX_FILE ${PROJECT_BINARY_DIR}/${PROJECT_NAME}.hex) 78 | set(BIN_FILE ${PROJECT_BINARY_DIR}/${PROJECT_NAME}.bin) 79 | 80 | add_custom_command(TARGET ${PROJECT_NAME}.elf POST_BUILD 81 | COMMAND ${CMAKE_OBJCOPY} -Oihex $ ${HEX_FILE} 82 | COMMAND ${CMAKE_OBJCOPY} -Obinary $ ${BIN_FILE} 83 | COMMENT "Building ${HEX_FILE} 84 | Building ${BIN_FILE}") 85 | -------------------------------------------------------------------------------- /Code Project/CMakeLists_template.txt: -------------------------------------------------------------------------------- 1 | #${templateWarning} 2 | set(CMAKE_SYSTEM_NAME Generic) 3 | set(CMAKE_SYSTEM_VERSION 1) 4 | ${cmakeRequiredVersion} 5 | # specify cross compilers and tools 6 | set(CMAKE_C_COMPILER arm-none-eabi-gcc) 7 | set(CMAKE_CXX_COMPILER arm-none-eabi-g++) 8 | set(CMAKE_ASM_COMPILER arm-none-eabi-gcc) 9 | set(CMAKE_AR arm-none-eabi-ar) 10 | set(CMAKE_OBJCOPY arm-none-eabi-objcopy) 11 | set(CMAKE_OBJDUMP arm-none-eabi-objdump) 12 | set(SIZE arm-none-eabi-size) 13 | set(CMAKE_TRY_COMPILE_TARGET_TYPE STATIC_LIBRARY) 14 | 15 | # project settings 16 | project(${projectName} C CXX ASM) 17 | set(CMAKE_CXX_STANDARD 17) 18 | set(CMAKE_C_STANDARD 11) 19 | 20 | #Uncomment for hardware floating point 21 | add_compile_definitions(ARM_MATH_CM4;ARM_MATH_MATRIX_CHECK;ARM_MATH_ROUNDING) 22 | add_compile_options(-mfloat-abi=hard -mfpu=fpv5-d16) 23 | add_link_options(-mfloat-abi=hard -mfpu=fpv5-d16) 24 | 25 | #Uncomment for software floating point 26 | #add_compile_options(-mfloat-abi=soft) 27 | 28 | add_compile_options(-mcpu=${mcpu} -mthumb -mthumb-interwork) 29 | add_compile_options(-ffunction-sections -fdata-sections -fno-common -fmessage-length=0) 30 | 31 | # uncomment to mitigate c++17 absolute addresses warnings 32 | #set(CMAKE_CXX_FLAGS "$${CMAKE_CXX_FLAGS} -Wno-register") 33 | 34 | if ("$${CMAKE_BUILD_TYPE}" STREQUAL "Release") 35 | message(STATUS "Maximum optimization for speed") 36 | add_compile_options(-Ofast) 37 | elseif ("$${CMAKE_BUILD_TYPE}" STREQUAL "RelWithDebInfo") 38 | message(STATUS "Maximum optimization for speed, debug info included") 39 | add_compile_options(-Ofast -g) 40 | elseif ("$${CMAKE_BUILD_TYPE}" STREQUAL "MinSizeRel") 41 | message(STATUS "Maximum optimization for size") 42 | add_compile_options(-Os) 43 | else () 44 | message(STATUS "Minimal optimization, debug info included") 45 | add_compile_options(-Og -g) 46 | endif () 47 | 48 | include_directories(${includes}) 49 | 50 | add_definitions(${defines}) 51 | 52 | file(GLOB_RECURSE SOURCES ${sources}) 53 | 54 | set(LINKER_SCRIPT $${CMAKE_SOURCE_DIR}/${linkerScript}) 55 | 56 | add_link_options(-Wl,-gc-sections,--print-memory-usage,-Map=$${PROJECT_BINARY_DIR}/$${PROJECT_NAME}.map) 57 | add_link_options(-mcpu=${mcpu} -mthumb -mthumb-interwork) 58 | add_link_options(-T $${LINKER_SCRIPT}) 59 | 60 | add_executable($${PROJECT_NAME}.elf $${SOURCES} $${LINKER_SCRIPT}) 61 | 62 | set(HEX_FILE $${PROJECT_BINARY_DIR}/$${PROJECT_NAME}.hex) 63 | set(BIN_FILE $${PROJECT_BINARY_DIR}/$${PROJECT_NAME}.bin) 64 | 65 | add_custom_command(TARGET $${PROJECT_NAME}.elf POST_BUILD 66 | COMMAND $${CMAKE_OBJCOPY} -Oihex $ $${HEX_FILE} 67 | COMMAND $${CMAKE_OBJCOPY} -Obinary $ $${BIN_FILE} 68 | COMMENT "Building $${HEX_FILE} 69 | Building $${BIN_FILE}") 70 | -------------------------------------------------------------------------------- /Code Project/Core/Inc/adc.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file adc.h 4 | * @brief This file contains all the function prototypes for 5 | * the adc.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2021 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __ADC_H__ 21 | #define __ADC_H__ 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "main.h" 29 | 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | extern ADC_HandleTypeDef hadc1; 35 | extern ADC_HandleTypeDef hadc2; 36 | 37 | /* USER CODE BEGIN Private defines */ 38 | 39 | /* USER CODE END Private defines */ 40 | 41 | void MX_ADC1_Init(void); 42 | void MX_ADC2_Init(void); 43 | 44 | /* USER CODE BEGIN Prototypes */ 45 | 46 | /* USER CODE END Prototypes */ 47 | 48 | #ifdef __cplusplus 49 | } 50 | #endif 51 | 52 | #endif /* __ADC_H__ */ 53 | 54 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 55 | -------------------------------------------------------------------------------- /Code Project/Core/Inc/dma.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file dma.h 4 | * @brief This file contains all the function prototypes for 5 | * the dma.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2021 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __DMA_H__ 21 | #define __DMA_H__ 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "main.h" 29 | 30 | /* DMA memory to memory transfer handles -------------------------------------*/ 31 | 32 | /* USER CODE BEGIN Includes */ 33 | 34 | /* USER CODE END Includes */ 35 | 36 | /* USER CODE BEGIN Private defines */ 37 | 38 | /* USER CODE END Private defines */ 39 | 40 | void MX_DMA_Init(void); 41 | 42 | /* USER CODE BEGIN Prototypes */ 43 | 44 | /* USER CODE END Prototypes */ 45 | 46 | #ifdef __cplusplus 47 | } 48 | #endif 49 | 50 | #endif /* __DMA_H__ */ 51 | 52 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 53 | -------------------------------------------------------------------------------- /Code Project/Core/Inc/gpio.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file gpio.h 4 | * @brief This file contains all the function prototypes for 5 | * the gpio.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2021 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __GPIO_H__ 21 | #define __GPIO_H__ 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "main.h" 29 | 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | /* USER CODE BEGIN Private defines */ 35 | 36 | /* USER CODE END Private defines */ 37 | 38 | void MX_GPIO_Init(void); 39 | 40 | /* USER CODE BEGIN Prototypes */ 41 | 42 | /* USER CODE END Prototypes */ 43 | 44 | #ifdef __cplusplus 45 | } 46 | #endif 47 | #endif /*__ GPIO_H__ */ 48 | 49 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 50 | -------------------------------------------------------------------------------- /Code Project/Core/Inc/i2c.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file i2c.h 4 | * @brief This file contains all the function prototypes for 5 | * the i2c.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2021 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __I2C_H__ 21 | #define __I2C_H__ 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "main.h" 29 | 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | extern I2C_HandleTypeDef hi2c1; 35 | extern I2C_HandleTypeDef hi2c2; 36 | extern I2C_HandleTypeDef hi2c4; 37 | 38 | /* USER CODE BEGIN Private defines */ 39 | 40 | /* USER CODE END Private defines */ 41 | 42 | void MX_I2C1_Init(void); 43 | void MX_I2C2_Init(void); 44 | void MX_I2C4_Init(void); 45 | 46 | /* USER CODE BEGIN Prototypes */ 47 | 48 | /* USER CODE END Prototypes */ 49 | 50 | #ifdef __cplusplus 51 | } 52 | #endif 53 | 54 | #endif /* __I2C_H__ */ 55 | 56 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 57 | -------------------------------------------------------------------------------- /Code Project/Core/Inc/main.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file : main.h 5 | * @brief : Header for main.c file. 6 | * This file contains the common defines of the application. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | *

© Copyright (c) 2021 STMicroelectronics. 11 | * All rights reserved.

12 | * 13 | * This software component is licensed by ST under Ultimate Liberty license 14 | * SLA0044, the "License"; You may not use this file except in compliance with 15 | * the License. You may obtain a copy of the License at: 16 | * www.st.com/SLA0044 17 | * 18 | ****************************************************************************** 19 | */ 20 | /* USER CODE END Header */ 21 | 22 | /* Define to prevent recursive inclusion -------------------------------------*/ 23 | #ifndef __MAIN_H 24 | #define __MAIN_H 25 | 26 | #ifdef __cplusplus 27 | extern "C" { 28 | #endif 29 | 30 | /* Includes ------------------------------------------------------------------*/ 31 | #include "stm32h7xx_hal.h" 32 | #include "stm32h7xx_hal.h" 33 | 34 | /* Private includes ----------------------------------------------------------*/ 35 | /* USER CODE BEGIN Includes */ 36 | 37 | /* USER CODE END Includes */ 38 | 39 | /* Exported types ------------------------------------------------------------*/ 40 | /* USER CODE BEGIN ET */ 41 | 42 | /* USER CODE END ET */ 43 | 44 | /* Exported constants --------------------------------------------------------*/ 45 | /* USER CODE BEGIN EC */ 46 | 47 | /* USER CODE END EC */ 48 | 49 | /* Exported macro ------------------------------------------------------------*/ 50 | /* USER CODE BEGIN EM */ 51 | 52 | /* USER CODE END EM */ 53 | 54 | /* Exported functions prototypes ---------------------------------------------*/ 55 | void Error_Handler(void); 56 | 57 | /* USER CODE BEGIN EFP */ 58 | 59 | /* USER CODE END EFP */ 60 | 61 | /* Private defines -----------------------------------------------------------*/ 62 | #define E3_Pin GPIO_PIN_3 63 | #define E3_GPIO_Port GPIOE 64 | #define RGB_R_Pin GPIO_PIN_4 65 | #define RGB_R_GPIO_Port GPIOE 66 | #define RGB_G_Pin GPIO_PIN_5 67 | #define RGB_G_GPIO_Port GPIOE 68 | #define RGB_B_Pin GPIO_PIN_6 69 | #define RGB_B_GPIO_Port GPIOE 70 | #define KEY1_Pin GPIO_PIN_13 71 | #define KEY1_GPIO_Port GPIOC 72 | #define KEY1_EXTI_IRQn EXTI15_10_IRQn 73 | #define KEY2_Pin GPIO_PIN_0 74 | #define KEY2_GPIO_Port GPIOC 75 | #define KEY2_EXTI_IRQn EXTI0_IRQn 76 | #define Safe_Pin GPIO_PIN_2 77 | #define Safe_GPIO_Port GPIOC 78 | #define Safe_EXTI_IRQn EXTI2_IRQn 79 | #define SPI6_CS_Pin GPIO_PIN_4 80 | #define SPI6_CS_GPIO_Port GPIOA 81 | #define LCD_BLK_Pin GPIO_PIN_10 82 | #define LCD_BLK_GPIO_Port GPIOE 83 | #define SPI4_CS_Pin GPIO_PIN_11 84 | #define SPI4_CS_GPIO_Port GPIOE 85 | #define LCD_WR_RS_Pin GPIO_PIN_13 86 | #define LCD_WR_RS_GPIO_Port GPIOE 87 | #define SPI2_CS_Pin GPIO_PIN_12 88 | #define SPI2_CS_GPIO_Port GPIOB 89 | #define SDMMC_DETECT_Pin GPIO_PIN_4 90 | #define SDMMC_DETECT_GPIO_Port GPIOD 91 | #define SPI1_BARO_CS_Pin GPIO_PIN_5 92 | #define SPI1_BARO_CS_GPIO_Port GPIOD 93 | #define SPI1_FLASH_CS_Pin GPIO_PIN_6 94 | #define SPI1_FLASH_CS_GPIO_Port GPIOD 95 | #define SBUS_INV_Pin GPIO_PIN_9 96 | #define SBUS_INV_GPIO_Port GPIOB 97 | /* USER CODE BEGIN Private defines */ 98 | 99 | /* USER CODE END Private defines */ 100 | 101 | #ifdef __cplusplus 102 | } 103 | #endif 104 | 105 | #endif /* __MAIN_H */ 106 | 107 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 108 | -------------------------------------------------------------------------------- /Code Project/Core/Inc/sdmmc.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file sdmmc.h 4 | * @brief This file contains all the function prototypes for 5 | * the sdmmc.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2021 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __SDMMC_H__ 21 | #define __SDMMC_H__ 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "main.h" 29 | 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | extern SD_HandleTypeDef hsd1; 35 | 36 | /* USER CODE BEGIN Private defines */ 37 | 38 | /* USER CODE END Private defines */ 39 | 40 | void MX_SDMMC1_SD_Init(void); 41 | 42 | /* USER CODE BEGIN Prototypes */ 43 | 44 | /* USER CODE END Prototypes */ 45 | 46 | #ifdef __cplusplus 47 | } 48 | #endif 49 | 50 | #endif /* __SDMMC_H__ */ 51 | 52 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 53 | -------------------------------------------------------------------------------- /Code Project/Core/Inc/spi.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file spi.h 4 | * @brief This file contains all the function prototypes for 5 | * the spi.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2021 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __SPI_H__ 21 | #define __SPI_H__ 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "main.h" 29 | 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | extern SPI_HandleTypeDef hspi1; 35 | extern SPI_HandleTypeDef hspi2; 36 | extern SPI_HandleTypeDef hspi4; 37 | extern SPI_HandleTypeDef hspi6; 38 | 39 | /* USER CODE BEGIN Private defines */ 40 | 41 | /* USER CODE END Private defines */ 42 | 43 | void MX_SPI1_Init(void); 44 | void MX_SPI2_Init(void); 45 | void MX_SPI4_Init(void); 46 | void MX_SPI6_Init(void); 47 | 48 | /* USER CODE BEGIN Prototypes */ 49 | 50 | /* USER CODE END Prototypes */ 51 | 52 | #ifdef __cplusplus 53 | } 54 | #endif 55 | 56 | #endif /* __SPI_H__ */ 57 | 58 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 59 | -------------------------------------------------------------------------------- /Code Project/Core/Inc/stm32h7xx_it.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file stm32h7xx_it.h 5 | * @brief This file contains the headers of the interrupt handlers. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2021 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | 21 | /* Define to prevent recursive inclusion -------------------------------------*/ 22 | #ifndef __STM32H7xx_IT_H 23 | #define __STM32H7xx_IT_H 24 | 25 | #ifdef __cplusplus 26 | extern "C" { 27 | #endif 28 | 29 | /* Private includes ----------------------------------------------------------*/ 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | /* Exported types ------------------------------------------------------------*/ 35 | /* USER CODE BEGIN ET */ 36 | 37 | /* USER CODE END ET */ 38 | 39 | /* Exported constants --------------------------------------------------------*/ 40 | /* USER CODE BEGIN EC */ 41 | 42 | /* USER CODE END EC */ 43 | 44 | /* Exported macro ------------------------------------------------------------*/ 45 | /* USER CODE BEGIN EM */ 46 | 47 | /* USER CODE END EM */ 48 | 49 | /* Exported functions prototypes ---------------------------------------------*/ 50 | void NMI_Handler(void); 51 | void HardFault_Handler(void); 52 | void MemManage_Handler(void); 53 | void BusFault_Handler(void); 54 | void UsageFault_Handler(void); 55 | void DebugMon_Handler(void); 56 | void EXTI0_IRQHandler(void); 57 | void EXTI2_IRQHandler(void); 58 | void DMA1_Stream0_IRQHandler(void); 59 | void DMA1_Stream1_IRQHandler(void); 60 | void DMA1_Stream2_IRQHandler(void); 61 | void DMA1_Stream5_IRQHandler(void); 62 | void DMA1_Stream6_IRQHandler(void); 63 | void USART1_IRQHandler(void); 64 | void USART3_IRQHandler(void); 65 | void EXTI15_10_IRQHandler(void); 66 | void SDMMC1_IRQHandler(void); 67 | void UART4_IRQHandler(void); 68 | void UART5_IRQHandler(void); 69 | void TIM6_DAC_IRQHandler(void); 70 | void TIM7_IRQHandler(void); 71 | void DMA2_Stream0_IRQHandler(void); 72 | void DMA2_Stream1_IRQHandler(void); 73 | void DMA2_Stream2_IRQHandler(void); 74 | void UART7_IRQHandler(void); 75 | void UART8_IRQHandler(void); 76 | void OTG_FS_EP1_OUT_IRQHandler(void); 77 | void OTG_FS_EP1_IN_IRQHandler(void); 78 | void OTG_FS_IRQHandler(void); 79 | /* USER CODE BEGIN EFP */ 80 | 81 | /* USER CODE END EFP */ 82 | 83 | #ifdef __cplusplus 84 | } 85 | #endif 86 | 87 | #endif /* __STM32H7xx_IT_H */ 88 | 89 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 90 | -------------------------------------------------------------------------------- /Code Project/Core/Inc/tim.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file tim.h 4 | * @brief This file contains all the function prototypes for 5 | * the tim.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2021 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __TIM_H__ 21 | #define __TIM_H__ 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "main.h" 29 | 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | extern TIM_HandleTypeDef htim1; 35 | extern TIM_HandleTypeDef htim2; 36 | extern TIM_HandleTypeDef htim3; 37 | extern TIM_HandleTypeDef htim4; 38 | extern TIM_HandleTypeDef htim7; 39 | extern TIM_HandleTypeDef htim8; 40 | 41 | /* USER CODE BEGIN Private defines */ 42 | 43 | /* USER CODE END Private defines */ 44 | 45 | void MX_TIM1_Init(void); 46 | void MX_TIM2_Init(void); 47 | void MX_TIM3_Init(void); 48 | void MX_TIM4_Init(void); 49 | void MX_TIM7_Init(void); 50 | void MX_TIM8_Init(void); 51 | 52 | void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim); 53 | 54 | /* USER CODE BEGIN Prototypes */ 55 | 56 | /* USER CODE END Prototypes */ 57 | 58 | #ifdef __cplusplus 59 | } 60 | #endif 61 | 62 | #endif /* __TIM_H__ */ 63 | 64 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 65 | -------------------------------------------------------------------------------- /Code Project/Core/Inc/usart.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file usart.h 4 | * @brief This file contains all the function prototypes for 5 | * the usart.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2021 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __USART_H__ 21 | #define __USART_H__ 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "main.h" 29 | 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | extern UART_HandleTypeDef huart4; 35 | extern UART_HandleTypeDef huart5; 36 | extern UART_HandleTypeDef huart7; 37 | extern UART_HandleTypeDef huart8; 38 | extern UART_HandleTypeDef huart1; 39 | extern UART_HandleTypeDef huart3; 40 | 41 | /* USER CODE BEGIN Private defines */ 42 | 43 | /* USER CODE END Private defines */ 44 | 45 | void MX_UART4_Init(void); 46 | void MX_UART5_Init(void); 47 | void MX_UART7_Init(void); 48 | void MX_UART8_Init(void); 49 | void MX_USART1_UART_Init(void); 50 | void MX_USART3_UART_Init(void); 51 | 52 | /* USER CODE BEGIN Prototypes */ 53 | 54 | /* USER CODE END Prototypes */ 55 | 56 | #ifdef __cplusplus 57 | } 58 | #endif 59 | 60 | #endif /* __USART_H__ */ 61 | 62 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 63 | -------------------------------------------------------------------------------- /Code Project/Core/Src/dma.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file dma.c 4 | * @brief This file provides code for the configuration 5 | * of all the requested memory to memory DMA transfers. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2021 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | 20 | /* Includes ------------------------------------------------------------------*/ 21 | #include "dma.h" 22 | 23 | /* USER CODE BEGIN 0 */ 24 | 25 | /* USER CODE END 0 */ 26 | 27 | /*----------------------------------------------------------------------------*/ 28 | /* Configure DMA */ 29 | /*----------------------------------------------------------------------------*/ 30 | 31 | /* USER CODE BEGIN 1 */ 32 | 33 | /* USER CODE END 1 */ 34 | 35 | /** 36 | * Enable DMA controller clock 37 | */ 38 | void MX_DMA_Init(void) 39 | { 40 | 41 | /* DMA controller clock enable */ 42 | __HAL_RCC_DMA1_CLK_ENABLE(); 43 | __HAL_RCC_DMA2_CLK_ENABLE(); 44 | 45 | /* DMA interrupt init */ 46 | /* DMA1_Stream0_IRQn interrupt configuration */ 47 | HAL_NVIC_SetPriority(DMA1_Stream0_IRQn, 5, 0); 48 | HAL_NVIC_EnableIRQ(DMA1_Stream0_IRQn); 49 | /* DMA1_Stream1_IRQn interrupt configuration */ 50 | HAL_NVIC_SetPriority(DMA1_Stream1_IRQn, 5, 0); 51 | HAL_NVIC_EnableIRQ(DMA1_Stream1_IRQn); 52 | /* DMA1_Stream2_IRQn interrupt configuration */ 53 | HAL_NVIC_SetPriority(DMA1_Stream2_IRQn, 5, 0); 54 | HAL_NVIC_EnableIRQ(DMA1_Stream2_IRQn); 55 | /* DMA1_Stream5_IRQn interrupt configuration */ 56 | HAL_NVIC_SetPriority(DMA1_Stream5_IRQn, 5, 0); 57 | HAL_NVIC_EnableIRQ(DMA1_Stream5_IRQn); 58 | /* DMA1_Stream6_IRQn interrupt configuration */ 59 | HAL_NVIC_SetPriority(DMA1_Stream6_IRQn, 5, 0); 60 | HAL_NVIC_EnableIRQ(DMA1_Stream6_IRQn); 61 | /* DMA2_Stream0_IRQn interrupt configuration */ 62 | HAL_NVIC_SetPriority(DMA2_Stream0_IRQn, 5, 0); 63 | HAL_NVIC_EnableIRQ(DMA2_Stream0_IRQn); 64 | /* DMA2_Stream1_IRQn interrupt configuration */ 65 | HAL_NVIC_SetPriority(DMA2_Stream1_IRQn, 5, 0); 66 | HAL_NVIC_EnableIRQ(DMA2_Stream1_IRQn); 67 | /* DMA2_Stream2_IRQn interrupt configuration */ 68 | HAL_NVIC_SetPriority(DMA2_Stream2_IRQn, 5, 0); 69 | HAL_NVIC_EnableIRQ(DMA2_Stream2_IRQn); 70 | 71 | } 72 | 73 | /* USER CODE BEGIN 2 */ 74 | 75 | /* USER CODE END 2 */ 76 | 77 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 78 | -------------------------------------------------------------------------------- /Code Project/Core/Src/stm32h7xx_hal_msp.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file stm32h7xx_hal_msp.c 5 | * @brief This file provides code for the MSP Initialization 6 | * and de-Initialization codes. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | *

© Copyright (c) 2021 STMicroelectronics. 11 | * All rights reserved.

12 | * 13 | * This software component is licensed by ST under Ultimate Liberty license 14 | * SLA0044, the "License"; You may not use this file except in compliance with 15 | * the License. You may obtain a copy of the License at: 16 | * www.st.com/SLA0044 17 | * 18 | ****************************************************************************** 19 | */ 20 | /* USER CODE END Header */ 21 | 22 | /* Includes ------------------------------------------------------------------*/ 23 | #include "main.h" 24 | /* USER CODE BEGIN Includes */ 25 | 26 | /* USER CODE END Includes */ 27 | 28 | /* Private typedef -----------------------------------------------------------*/ 29 | /* USER CODE BEGIN TD */ 30 | 31 | /* USER CODE END TD */ 32 | 33 | /* Private define ------------------------------------------------------------*/ 34 | /* USER CODE BEGIN Define */ 35 | 36 | /* USER CODE END Define */ 37 | 38 | /* Private macro -------------------------------------------------------------*/ 39 | /* USER CODE BEGIN Macro */ 40 | 41 | /* USER CODE END Macro */ 42 | 43 | /* Private variables ---------------------------------------------------------*/ 44 | /* USER CODE BEGIN PV */ 45 | 46 | /* USER CODE END PV */ 47 | 48 | /* Private function prototypes -----------------------------------------------*/ 49 | /* USER CODE BEGIN PFP */ 50 | 51 | /* USER CODE END PFP */ 52 | 53 | /* External functions --------------------------------------------------------*/ 54 | /* USER CODE BEGIN ExternalFunctions */ 55 | 56 | /* USER CODE END ExternalFunctions */ 57 | 58 | /* USER CODE BEGIN 0 */ 59 | 60 | /* USER CODE END 0 */ 61 | /** 62 | * Initializes the Global MSP. 63 | */ 64 | void HAL_MspInit(void) 65 | { 66 | /* USER CODE BEGIN MspInit 0 */ 67 | 68 | /* USER CODE END MspInit 0 */ 69 | 70 | __HAL_RCC_SYSCFG_CLK_ENABLE(); 71 | 72 | /* System interrupt init*/ 73 | /* PendSV_IRQn interrupt configuration */ 74 | HAL_NVIC_SetPriority(PendSV_IRQn, 15, 0); 75 | 76 | /* USER CODE BEGIN MspInit 1 */ 77 | 78 | /* USER CODE END MspInit 1 */ 79 | } 80 | 81 | /* USER CODE BEGIN 1 */ 82 | 83 | /* USER CODE END 1 */ 84 | 85 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 86 | -------------------------------------------------------------------------------- /Code Project/Core/Src/syscalls.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file syscalls.c 4 | * @author Auto-generated by STM32CubeIDE 5 | * @brief STM32CubeIDE Minimal System calls file 6 | * 7 | * For more information about which c-functions 8 | * need which of these lowlevel functions 9 | * please consult the Newlib libc-manual 10 | ****************************************************************************** 11 | * @attention 12 | * 13 | *

© Copyright (c) 2020 STMicroelectronics. 14 | * All rights reserved.

15 | * 16 | * This software component is licensed by ST under BSD 3-Clause license, 17 | * the "License"; You may not use this file except in compliance with the 18 | * License. You may obtain a copy of the License at: 19 | * opensource.org/licenses/BSD-3-Clause 20 | * 21 | ****************************************************************************** 22 | */ 23 | 24 | /* Includes */ 25 | #include 26 | #include 27 | #include 28 | #include 29 | #include 30 | #include 31 | #include 32 | #include 33 | 34 | 35 | /* Variables */ 36 | //#undef errno 37 | extern int errno; 38 | extern int __io_putchar(int ch) __attribute__((weak)); 39 | extern int __io_getchar(void) __attribute__((weak)); 40 | 41 | register char * stack_ptr asm("sp"); 42 | 43 | char *__env[1] = { 0 }; 44 | char **environ = __env; 45 | 46 | 47 | /* Functions */ 48 | void initialise_monitor_handles() 49 | { 50 | } 51 | 52 | int _getpid(void) 53 | { 54 | return 1; 55 | } 56 | 57 | int _kill(int pid, int sig) 58 | { 59 | errno = EINVAL; 60 | return -1; 61 | } 62 | 63 | void _exit (int status) 64 | { 65 | _kill(status, -1); 66 | while (1) {} /* Make sure we hang here */ 67 | } 68 | 69 | __attribute__((weak)) int _read(int file, char *ptr, int len) 70 | { 71 | int DataIdx; 72 | 73 | for (DataIdx = 0; DataIdx < len; DataIdx++) 74 | { 75 | *ptr++ = __io_getchar(); 76 | } 77 | 78 | return len; 79 | } 80 | 81 | __attribute__((weak)) int _write(int file, char *ptr, int len) 82 | { 83 | int DataIdx; 84 | 85 | for (DataIdx = 0; DataIdx < len; DataIdx++) 86 | { 87 | __io_putchar(*ptr++); 88 | } 89 | return len; 90 | } 91 | 92 | int _close(int file) 93 | { 94 | return -1; 95 | } 96 | 97 | 98 | int _fstat(int file, struct stat *st) 99 | { 100 | st->st_mode = S_IFCHR; 101 | return 0; 102 | } 103 | 104 | int _isatty(int file) 105 | { 106 | return 1; 107 | } 108 | 109 | int _lseek(int file, int ptr, int dir) 110 | { 111 | return 0; 112 | } 113 | 114 | int _open(char *path, int flags, ...) 115 | { 116 | /* Pretend like we always fail */ 117 | return -1; 118 | } 119 | 120 | int _wait(int *status) 121 | { 122 | errno = ECHILD; 123 | return -1; 124 | } 125 | 126 | int _unlink(char *name) 127 | { 128 | errno = ENOENT; 129 | return -1; 130 | } 131 | 132 | int _times(struct tms *buf) 133 | { 134 | return -1; 135 | } 136 | 137 | int _stat(char *file, struct stat *st) 138 | { 139 | st->st_mode = S_IFCHR; 140 | return 0; 141 | } 142 | 143 | int _link(char *old, char *new) 144 | { 145 | errno = EMLINK; 146 | return -1; 147 | } 148 | 149 | int _fork(void) 150 | { 151 | errno = EAGAIN; 152 | return -1; 153 | } 154 | 155 | int _execve(char *name, char **argv, char **env) 156 | { 157 | errno = ENOMEM; 158 | return -1; 159 | } 160 | -------------------------------------------------------------------------------- /Code Project/Core/Src/sysmem.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file sysmem.c 4 | * @author Generated by STM32CubeIDE 5 | * @brief STM32CubeIDE System Memory calls file 6 | * 7 | * For more information about which C functions 8 | * need which of these lowlevel functions 9 | * please consult the newlib libc manual 10 | ****************************************************************************** 11 | * @attention 12 | * 13 | *

© Copyright (c) 2020 STMicroelectronics. 14 | * All rights reserved.

15 | * 16 | * This software component is licensed by ST under BSD 3-Clause license, 17 | * the "License"; You may not use this file except in compliance with the 18 | * License. You may obtain a copy of the License at: 19 | * opensource.org/licenses/BSD-3-Clause 20 | * 21 | ****************************************************************************** 22 | */ 23 | 24 | /* Includes */ 25 | #include 26 | #include 27 | 28 | /** 29 | * Pointer to the current high watermark of the heap usage 30 | */ 31 | static uint8_t *__sbrk_heap_end = NULL; 32 | 33 | /** 34 | * @brief _sbrk() allocates memory to the newlib heap and is used by malloc 35 | * and others from the C library 36 | * 37 | * @verbatim 38 | * ############################################################################ 39 | * # .data # .bss # newlib heap # MSP stack # 40 | * # # # # Reserved by _Min_Stack_Size # 41 | * ############################################################################ 42 | * ^-- RAM start ^-- _end _estack, RAM end --^ 43 | * @endverbatim 44 | * 45 | * This implementation starts allocating at the '_end' linker symbol 46 | * The '_Min_Stack_Size' linker symbol reserves a memory for the MSP stack 47 | * The implementation considers '_estack' linker symbol to be RAM end 48 | * NOTE: If the MSP stack, at any point during execution, grows larger than the 49 | * reserved size, please increase the '_Min_Stack_Size'. 50 | * 51 | * @param incr Memory size 52 | * @return Pointer to allocated memory 53 | */ 54 | void *_sbrk(ptrdiff_t incr) 55 | { 56 | extern uint8_t _end; /* Symbol defined in the linker script */ 57 | extern uint8_t _estack; /* Symbol defined in the linker script */ 58 | extern uint32_t _Min_Stack_Size; /* Symbol defined in the linker script */ 59 | const uint32_t stack_limit = (uint32_t)&_estack - (uint32_t)&_Min_Stack_Size; 60 | const uint8_t *max_heap = (uint8_t *)stack_limit; 61 | uint8_t *prev_heap_end; 62 | 63 | /* Initialize heap end at first call */ 64 | if (NULL == __sbrk_heap_end) 65 | { 66 | __sbrk_heap_end = &_end; 67 | } 68 | 69 | /* Protect heap from growing into the reserved MSP stack */ 70 | if (__sbrk_heap_end + incr > max_heap) 71 | { 72 | errno = ENOMEM; 73 | return (void *)-1; 74 | } 75 | 76 | prev_heap_end = __sbrk_heap_end; 77 | __sbrk_heap_end += incr; 78 | 79 | return (void *)prev_heap_end; 80 | } 81 | -------------------------------------------------------------------------------- /Code Project/Drivers/CMSIS/Device/ST/STM32H7xx/Include/stm32h7xx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/makermare/UAV-FlyingControlSystem-BlueSkyFlightControl/d35d104cc8a21090000b984fbafd00f08f8a0f3e/Code Project/Drivers/CMSIS/Device/ST/STM32H7xx/Include/stm32h7xx.h -------------------------------------------------------------------------------- /Code Project/Drivers/CMSIS/Device/ST/STM32H7xx/Include/system_stm32h7xx.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file system_stm32h7xx.h 4 | * @author MCD Application Team 5 | * @brief CMSIS Cortex-Mx Device System Source File for STM32H7xx devices. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2017 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under BSD 3-Clause license, 13 | * the "License"; You may not use this file except in compliance with the 14 | * License. You may obtain a copy of the License at: 15 | * opensource.org/licenses/BSD-3-Clause 16 | * 17 | ****************************************************************************** 18 | */ 19 | 20 | /** @addtogroup CMSIS 21 | * @{ 22 | */ 23 | 24 | /** @addtogroup stm32h7xx_system 25 | * @{ 26 | */ 27 | 28 | /** 29 | * @brief Define to prevent recursive inclusion 30 | */ 31 | #ifndef SYSTEM_STM32H7XX_H 32 | #define SYSTEM_STM32H7XX_H 33 | 34 | #ifdef __cplusplus 35 | extern "C" { 36 | #endif 37 | 38 | /** @addtogroup STM32H7xx_System_Includes 39 | * @{ 40 | */ 41 | 42 | /** 43 | * @} 44 | */ 45 | 46 | 47 | /** @addtogroup STM32H7xx_System_Exported_types 48 | * @{ 49 | */ 50 | /* This variable is updated in three ways: 51 | 1) by calling CMSIS function SystemCoreClockUpdate() 52 | 2) by calling HAL API function HAL_RCC_GetSysClockFreq() 53 | 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency 54 | Note: If you use this function to configure the system clock; then there 55 | is no need to call the 2 first functions listed above, since SystemCoreClock 56 | variable is updated automatically. 57 | */ 58 | extern uint32_t SystemCoreClock; /*!< System Domain1 Clock Frequency */ 59 | extern uint32_t SystemD2Clock; /*!< System Domain2 Clock Frequency */ 60 | extern const uint8_t D1CorePrescTable[16] ; /*!< D1CorePrescTable prescalers table values */ 61 | 62 | /** 63 | * @} 64 | */ 65 | 66 | /** @addtogroup STM32H7xx_System_Exported_Constants 67 | * @{ 68 | */ 69 | 70 | /** 71 | * @} 72 | */ 73 | 74 | /** @addtogroup STM32H7xx_System_Exported_Macros 75 | * @{ 76 | */ 77 | 78 | /** 79 | * @} 80 | */ 81 | 82 | /** @addtogroup STM32H7xx_System_Exported_Functions 83 | * @{ 84 | */ 85 | 86 | extern void SystemInit(void); 87 | extern void SystemCoreClockUpdate(void); 88 | /** 89 | * @} 90 | */ 91 | 92 | #ifdef __cplusplus 93 | } 94 | #endif 95 | 96 | #endif /* SYSTEM_STM32H7XX_H */ 97 | 98 | /** 99 | * @} 100 | */ 101 | 102 | /** 103 | * @} 104 | */ 105 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 106 | -------------------------------------------------------------------------------- /Code Project/Drivers/CMSIS/Include/cmsis_version.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************//** 2 | * @file cmsis_version.h 3 | * @brief CMSIS Core(M) Version definitions 4 | * @version V5.0.2 5 | * @date 19. April 2017 6 | ******************************************************************************/ 7 | /* 8 | * Copyright (c) 2009-2017 ARM Limited. All rights reserved. 9 | * 10 | * SPDX-License-Identifier: Apache-2.0 11 | * 12 | * Licensed under the Apache License, Version 2.0 (the License); you may 13 | * not use this file except in compliance with the License. 14 | * You may obtain a copy of the License at 15 | * 16 | * www.apache.org/licenses/LICENSE-2.0 17 | * 18 | * Unless required by applicable law or agreed to in writing, software 19 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT 20 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | * See the License for the specific language governing permissions and 22 | * limitations under the License. 23 | */ 24 | 25 | #if defined ( __ICCARM__ ) 26 | #pragma system_include /* treat file as system include file for MISRA check */ 27 | #elif defined (__clang__) 28 | #pragma clang system_header /* treat file as system include file */ 29 | #endif 30 | 31 | #ifndef __CMSIS_VERSION_H 32 | #define __CMSIS_VERSION_H 33 | 34 | /* CMSIS Version definitions */ 35 | #define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */ 36 | #define __CM_CMSIS_VERSION_SUB ( 1U) /*!< [15:0] CMSIS Core(M) sub version */ 37 | #define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \ 38 | __CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */ 39 | #endif 40 | -------------------------------------------------------------------------------- /Code Project/Drivers/CMSIS/Include/tz_context.h: -------------------------------------------------------------------------------- 1 | /****************************************************************************** 2 | * @file tz_context.h 3 | * @brief Context Management for Armv8-M TrustZone 4 | * @version V1.0.1 5 | * @date 10. January 2018 6 | ******************************************************************************/ 7 | /* 8 | * Copyright (c) 2017-2018 Arm Limited. All rights reserved. 9 | * 10 | * SPDX-License-Identifier: Apache-2.0 11 | * 12 | * Licensed under the Apache License, Version 2.0 (the License); you may 13 | * not use this file except in compliance with the License. 14 | * You may obtain a copy of the License at 15 | * 16 | * www.apache.org/licenses/LICENSE-2.0 17 | * 18 | * Unless required by applicable law or agreed to in writing, software 19 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT 20 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | * See the License for the specific language governing permissions and 22 | * limitations under the License. 23 | */ 24 | 25 | #if defined ( __ICCARM__ ) 26 | #pragma system_include /* treat file as system include file for MISRA check */ 27 | #elif defined (__clang__) 28 | #pragma clang system_header /* treat file as system include file */ 29 | #endif 30 | 31 | #ifndef TZ_CONTEXT_H 32 | #define TZ_CONTEXT_H 33 | 34 | #include 35 | 36 | #ifndef TZ_MODULEID_T 37 | #define TZ_MODULEID_T 38 | /// \details Data type that identifies secure software modules called by a process. 39 | typedef uint32_t TZ_ModuleId_t; 40 | #endif 41 | 42 | /// \details TZ Memory ID identifies an allocated memory slot. 43 | typedef uint32_t TZ_MemoryId_t; 44 | 45 | /// Initialize secure context memory system 46 | /// \return execution status (1: success, 0: error) 47 | uint32_t TZ_InitContextSystem_S (void); 48 | 49 | /// Allocate context memory for calling secure software modules in TrustZone 50 | /// \param[in] module identifies software modules called from non-secure mode 51 | /// \return value != 0 id TrustZone memory slot identifier 52 | /// \return value 0 no memory available or internal error 53 | TZ_MemoryId_t TZ_AllocModuleContext_S (TZ_ModuleId_t module); 54 | 55 | /// Free context memory that was previously allocated with \ref TZ_AllocModuleContext_S 56 | /// \param[in] id TrustZone memory slot identifier 57 | /// \return execution status (1: success, 0: error) 58 | uint32_t TZ_FreeModuleContext_S (TZ_MemoryId_t id); 59 | 60 | /// Load secure context (called on RTOS thread context switch) 61 | /// \param[in] id TrustZone memory slot identifier 62 | /// \return execution status (1: success, 0: error) 63 | uint32_t TZ_LoadContext_S (TZ_MemoryId_t id); 64 | 65 | /// Store secure context (called on RTOS thread context switch) 66 | /// \param[in] id TrustZone memory slot identifier 67 | /// \return execution status (1: success, 0: error) 68 | uint32_t TZ_StoreContext_S (TZ_MemoryId_t id); 69 | 70 | #endif // TZ_CONTEXT_H 71 | -------------------------------------------------------------------------------- /Code Project/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_pcd_ex.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32h7xx_hal_pcd_ex.h 4 | * @author MCD Application Team 5 | * @brief Header file of PCD HAL Extension module. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2017 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under BSD 3-Clause license, 13 | * the "License"; You may not use this file except in compliance with the 14 | * License. You may obtain a copy of the License at: 15 | * opensource.org/licenses/BSD-3-Clause 16 | * 17 | ****************************************************************************** 18 | */ 19 | 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef STM32H7xx_HAL_PCD_EX_H 22 | #define STM32H7xx_HAL_PCD_EX_H 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "stm32h7xx_hal_def.h" 30 | 31 | #if defined (USB_OTG_FS) || defined (USB_OTG_HS) 32 | /** @addtogroup STM32H7xx_HAL_Driver 33 | * @{ 34 | */ 35 | 36 | /** @addtogroup PCDEx 37 | * @{ 38 | */ 39 | /* Exported types ------------------------------------------------------------*/ 40 | /* Exported constants --------------------------------------------------------*/ 41 | /* Exported macros -----------------------------------------------------------*/ 42 | /* Exported functions --------------------------------------------------------*/ 43 | /** @addtogroup PCDEx_Exported_Functions PCDEx Exported Functions 44 | * @{ 45 | */ 46 | /** @addtogroup PCDEx_Exported_Functions_Group1 Peripheral Control functions 47 | * @{ 48 | */ 49 | 50 | #if defined (USB_OTG_FS) || defined (USB_OTG_HS) 51 | HAL_StatusTypeDef HAL_PCDEx_SetTxFiFo(PCD_HandleTypeDef *hpcd, uint8_t fifo, uint16_t size); 52 | HAL_StatusTypeDef HAL_PCDEx_SetRxFiFo(PCD_HandleTypeDef *hpcd, uint16_t size); 53 | #endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ 54 | 55 | 56 | HAL_StatusTypeDef HAL_PCDEx_ActivateLPM(PCD_HandleTypeDef *hpcd); 57 | HAL_StatusTypeDef HAL_PCDEx_DeActivateLPM(PCD_HandleTypeDef *hpcd); 58 | 59 | 60 | HAL_StatusTypeDef HAL_PCDEx_ActivateBCD(PCD_HandleTypeDef *hpcd); 61 | HAL_StatusTypeDef HAL_PCDEx_DeActivateBCD(PCD_HandleTypeDef *hpcd); 62 | void HAL_PCDEx_BCD_VBUSDetect(PCD_HandleTypeDef *hpcd); 63 | 64 | void HAL_PCDEx_LPM_Callback(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg); 65 | void HAL_PCDEx_BCD_Callback(PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg); 66 | 67 | /** 68 | * @} 69 | */ 70 | 71 | /** 72 | * @} 73 | */ 74 | 75 | /** 76 | * @} 77 | */ 78 | 79 | /** 80 | * @} 81 | */ 82 | #endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ 83 | 84 | #ifdef __cplusplus 85 | } 86 | #endif 87 | 88 | 89 | #endif /* STM32H7xx_HAL_PCD_EX_H */ 90 | 91 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 92 | -------------------------------------------------------------------------------- /Code Project/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_hal_spi_ex.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32h7xx_hal_spi_ex.h 4 | * @author MCD Application Team 5 | * @brief Header file of SPI HAL Extended module. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2017 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under BSD 3-Clause license, 13 | * the "License"; You may not use this file except in compliance with the 14 | * License. You may obtain a copy of the License at: 15 | * opensource.org/licenses/BSD-3-Clause 16 | * 17 | ****************************************************************************** 18 | */ 19 | 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef STM32H7xx_HAL_SPI_EX_H 22 | #define STM32H7xx_HAL_SPI_EX_H 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "stm32h7xx_hal_def.h" 30 | 31 | /** @addtogroup STM32H7xx_HAL_Driver 32 | * @{ 33 | */ 34 | 35 | /** @addtogroup SPIEx 36 | * @{ 37 | */ 38 | 39 | /* Exported types ------------------------------------------------------------*/ 40 | /* Exported constants --------------------------------------------------------*/ 41 | /* Exported macros -----------------------------------------------------------*/ 42 | /* Exported functions --------------------------------------------------------*/ 43 | /** @addtogroup SPIEx_Exported_Functions 44 | * @{ 45 | */ 46 | 47 | /* Initialization and de-initialization functions ****************************/ 48 | /* IO operation functions *****************************************************/ 49 | /** @addtogroup SPIEx_Exported_Functions_Group1 50 | * @{ 51 | */ 52 | HAL_StatusTypeDef HAL_SPIEx_FlushRxFifo(SPI_HandleTypeDef *hspi); 53 | HAL_StatusTypeDef HAL_SPIEx_EnableLockConfiguration(SPI_HandleTypeDef *hspi); 54 | HAL_StatusTypeDef HAL_SPIEx_ConfigureUnderrun(SPI_HandleTypeDef *hspi, uint32_t UnderrunDetection, uint32_t UnderrunBehaviour); 55 | /** 56 | * @} 57 | */ 58 | 59 | /** 60 | * @} 61 | */ 62 | 63 | /** 64 | * @} 65 | */ 66 | 67 | /** 68 | * @} 69 | */ 70 | 71 | #ifdef __cplusplus 72 | } 73 | #endif 74 | 75 | #endif /* STM32H7xx_HAL_SPI_EX_H */ 76 | 77 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 78 | -------------------------------------------------------------------------------- /Code Project/Drivers/STM32H7xx_HAL_Driver/Inc/stm32h7xx_ll_delayblock.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32h7xx_ll_delayblock.h 4 | * @author MCD Application Team 5 | * @brief Header file of Delay Block module. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2017 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under BSD 3-Clause license, 13 | * the "License"; You may not use this file except in compliance with the 14 | * License. You may obtain a copy of the License at: 15 | * opensource.org/licenses/BSD-3-Clause 16 | * 17 | ****************************************************************************** 18 | */ 19 | 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef STM32H7xx_LL_DLYB_H 22 | #define STM32H7xx_LL_DLYB_H 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "stm32h7xx_hal_def.h" 30 | 31 | /** @addtogroup STM32H7xx_HAL_Driver 32 | * @{ 33 | */ 34 | 35 | /** @addtogroup DELAYBLOCK_LL 36 | * @{ 37 | */ 38 | 39 | /* Exported types ------------------------------------------------------------*/ 40 | /** @defgroup DELAYBLOCK_LL_Exported_Types DELAYBLOCK_LL Exported Types 41 | * @{ 42 | */ 43 | 44 | 45 | /** 46 | * @} 47 | */ 48 | 49 | /* Exported constants --------------------------------------------------------*/ 50 | /** @defgroup DLYB_Exported_Constants Delay Block Exported Constants 51 | * @{ 52 | */ 53 | 54 | 55 | #define DLYB_MAX_UNIT ((uint32_t)0x00000080U) /*!< Max UNIT value (128) */ 56 | #define DLYB_MAX_SELECT ((uint32_t)0x0000000CU) /*!< Max SELECT value (12) */ 57 | 58 | /** 59 | * @} 60 | */ 61 | 62 | /* Peripheral Control functions ************************************************/ 63 | /** @addtogroup HAL_DELAYBLOCK_LL_Group3 Delay Block functions 64 | * @{ 65 | */ 66 | HAL_StatusTypeDef DelayBlock_Enable(DLYB_TypeDef *DLYBx); 67 | HAL_StatusTypeDef DelayBlock_Disable(DLYB_TypeDef *DLYBx); 68 | HAL_StatusTypeDef DelayBlock_Configure(DLYB_TypeDef *DLYBx, uint32_t PhaseSel, uint32_t Units); 69 | 70 | /** 71 | * @} 72 | */ 73 | 74 | 75 | /** 76 | * @} 77 | */ 78 | 79 | /** 80 | * @} 81 | */ 82 | #ifdef __cplusplus 83 | } 84 | #endif 85 | 86 | #endif /* STM32H7xx_LL_DLYB_H */ 87 | 88 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 89 | -------------------------------------------------------------------------------- /Code Project/FATFS/App/fatfs.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file fatfs.c 4 | * @brief Code for fatfs applications 5 | ****************************************************************************** 6 | * @attention 7 | * 8 | *

© Copyright (c) 2021 STMicroelectronics. 9 | * All rights reserved.

10 | * 11 | * This software component is licensed by ST under Ultimate Liberty license 12 | * SLA0044, the "License"; You may not use this file except in compliance with 13 | * the License. You may obtain a copy of the License at: 14 | * www.st.com/SLA0044 15 | * 16 | ****************************************************************************** 17 | */ 18 | 19 | #include "fatfs.h" 20 | 21 | uint8_t retSD; /* Return value for SD */ 22 | char SDPath[4]; /* SD logical drive path */ 23 | FATFS SDFatFS; /* File system object for SD logical drive */ 24 | FIL SDFile; /* File object for SD */ 25 | 26 | /* USER CODE BEGIN Variables */ 27 | 28 | /* USER CODE END Variables */ 29 | 30 | void MX_FATFS_Init(void) 31 | { 32 | /*## FatFS: Link the SD driver ###########################*/ 33 | retSD = FATFS_LinkDriver(&SD_Driver, SDPath); 34 | 35 | /* USER CODE BEGIN Init */ 36 | /* additional user code for init */ 37 | /* USER CODE END Init */ 38 | } 39 | 40 | /** 41 | * @brief Gets Time from RTC 42 | * @param None 43 | * @retval Time in DWORD 44 | */ 45 | DWORD get_fattime(void) 46 | { 47 | /* USER CODE BEGIN get_fattime */ 48 | return 0; 49 | /* USER CODE END get_fattime */ 50 | } 51 | 52 | /* USER CODE BEGIN Application */ 53 | 54 | /* USER CODE END Application */ 55 | 56 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 57 | -------------------------------------------------------------------------------- /Code Project/FATFS/App/fatfs.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file fatfs.h 4 | * @brief Header for fatfs applications 5 | ****************************************************************************** 6 | * @attention 7 | * 8 | *

© Copyright (c) 2021 STMicroelectronics. 9 | * All rights reserved.

10 | * 11 | * This software component is licensed by ST under Ultimate Liberty license 12 | * SLA0044, the "License"; You may not use this file except in compliance with 13 | * the License. You may obtain a copy of the License at: 14 | * www.st.com/SLA0044 15 | * 16 | ****************************************************************************** 17 | */ 18 | 19 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __fatfs_H 21 | #define __fatfs_H 22 | #ifdef __cplusplus 23 | extern "C" { 24 | #endif 25 | 26 | #include "ff.h" 27 | #include "ff_gen_drv.h" 28 | #include "sd_diskio.h" /* defines SD_Driver as external */ 29 | 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | extern uint8_t retSD; /* Return value for SD */ 35 | extern char SDPath[4]; /* SD logical drive path */ 36 | extern FATFS SDFatFS; /* File system object for SD logical drive */ 37 | extern FIL SDFile; /* File object for SD */ 38 | 39 | void MX_FATFS_Init(void); 40 | 41 | /* USER CODE BEGIN Prototypes */ 42 | 43 | /* USER CODE END Prototypes */ 44 | #ifdef __cplusplus 45 | } 46 | #endif 47 | #endif /*__fatfs_H */ 48 | 49 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 50 | -------------------------------------------------------------------------------- /Code Project/FATFS/Target/bsp_driver_sd.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file bsp_driver_sd.h (based on stm32h743i_eval_sd.h) 4 | * @brief This file contains the common defines and functions prototypes for 5 | * the bsp_driver_sd.c driver. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2021 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __STM32H7_SD_H 22 | #define __STM32H7_SD_H 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "stm32h7xx_hal.h" 30 | #include "fatfs_platform.h" 31 | 32 | /* Exported types --------------------------------------------------------*/ 33 | /** 34 | * @brief SD Card information structure 35 | */ 36 | #define BSP_SD_CardInfo HAL_SD_CardInfoTypeDef 37 | 38 | /* Exported constants --------------------------------------------------------*/ 39 | /** 40 | * @brief SD status structure definition 41 | */ 42 | #define MSD_OK ((uint8_t)0x00) 43 | #define MSD_ERROR ((uint8_t)0x01) 44 | #define MSD_ERROR_SD_NOT_PRESENT ((uint8_t)0x02) 45 | 46 | /** 47 | * @brief SD transfer state definition 48 | */ 49 | #define SD_TRANSFER_OK ((uint8_t)0x00) 50 | #define SD_TRANSFER_BUSY ((uint8_t)0x01) 51 | 52 | #define SD_PRESENT ((uint8_t)0x01) 53 | #define SD_NOT_PRESENT ((uint8_t)0x00) 54 | #define SD_DATATIMEOUT ((uint32_t)100000000) 55 | 56 | /* USER CODE BEGIN BSP_H_CODE */ 57 | #define SD_DetectIRQHandler() HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_8) 58 | 59 | /* Exported functions --------------------------------------------------------*/ 60 | uint8_t BSP_SD_Init(void); 61 | uint8_t BSP_SD_ITConfig(void); 62 | uint8_t BSP_SD_ReadBlocks(uint32_t *pData, uint32_t ReadAddr, uint32_t NumOfBlocks, uint32_t Timeout); 63 | uint8_t BSP_SD_WriteBlocks(uint32_t *pData, uint32_t WriteAddr, uint32_t NumOfBlocks, uint32_t Timeout); 64 | uint8_t BSP_SD_ReadBlocks_DMA(uint32_t *pData, uint32_t ReadAddr, uint32_t NumOfBlocks); 65 | uint8_t BSP_SD_WriteBlocks_DMA(uint32_t *pData, uint32_t WriteAddr, uint32_t NumOfBlocks); 66 | uint8_t BSP_SD_Erase(uint32_t StartAddr, uint32_t EndAddr); 67 | uint8_t BSP_SD_GetCardState(void); 68 | void BSP_SD_GetCardInfo(BSP_SD_CardInfo *CardInfo); 69 | uint8_t BSP_SD_IsDetected(void); 70 | 71 | /* These functions can be modified in case the current settings (e.g. DMA stream) 72 | need to be changed for specific application needs */ 73 | void BSP_SD_AbortCallback(void); 74 | void BSP_SD_WriteCpltCallback(void); 75 | void BSP_SD_ReadCpltCallback(void); 76 | /* USER CODE END BSP_H_CODE */ 77 | 78 | #ifdef __cplusplus 79 | } 80 | #endif 81 | 82 | #endif /* __STM32H7_SD_H */ 83 | 84 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 85 | -------------------------------------------------------------------------------- /Code Project/FATFS/Target/fatfs_platform.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file : fatfs_platform.c 4 | * @brief : fatfs_platform source file 5 | ****************************************************************************** 6 | * @attention 7 | * 8 | *

© Copyright (c) 2021 STMicroelectronics. 9 | * All rights reserved.

10 | * 11 | * This software component is licensed by ST under Ultimate Liberty license 12 | * SLA0044, the "License"; You may not use this file except in compliance with 13 | * the License. You may obtain a copy of the License at: 14 | * www.st.com/SLA0044 15 | * 16 | ****************************************************************************** 17 | */ 18 | #include "fatfs_platform.h" 19 | 20 | uint8_t BSP_PlatformIsDetected(void) { 21 | uint8_t status = SD_PRESENT; 22 | /* Check SD card detect pin */ 23 | if(HAL_GPIO_ReadPin(SD_DETECT_GPIO_PORT, SD_DETECT_PIN) != GPIO_PIN_RESET) 24 | { 25 | status = SD_NOT_PRESENT; 26 | } 27 | /* USER CODE BEGIN 1 */ 28 | /* user code can be inserted here */ 29 | /* USER CODE END 1 */ 30 | return status; 31 | } 32 | -------------------------------------------------------------------------------- /Code Project/FATFS/Target/fatfs_platform.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file : fatfs_platform.h 4 | * @brief : fatfs_platform header file 5 | ****************************************************************************** 6 | * @attention 7 | * 8 | *

© Copyright (c) 2021 STMicroelectronics. 9 | * All rights reserved.

10 | * 11 | * This software component is licensed by ST under Ultimate Liberty license 12 | * SLA0044, the "License"; You may not use this file except in compliance with 13 | * the License. You may obtain a copy of the License at: 14 | * www.st.com/SLA0044 15 | * 16 | ****************************************************************************** 17 | */ 18 | /* Includes ------------------------------------------------------------------*/ 19 | #include "stm32h7xx_hal.h" 20 | /* Defines ------------------------------------------------------------------*/ 21 | #define SD_PRESENT ((uint8_t)0x01) /* also in bsp_driver_sd.h */ 22 | #define SD_NOT_PRESENT ((uint8_t)0x00) /* also in bsp_driver_sd.h */ 23 | #define SD_DETECT_PIN GPIO_PIN_4 24 | #define SD_DETECT_GPIO_PORT GPIOD 25 | /* Prototypes ---------------------------------------------------------------*/ 26 | uint8_t BSP_PlatformIsDetected(void); 27 | -------------------------------------------------------------------------------- /Code Project/FATFS/Target/sd_diskio.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file sd_diskio.h 5 | * @brief Header for sd_diskio.c module 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2021 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | 21 | /* Note: code generation based on sd_diskio_dma_rtos_template.h */ 22 | 23 | /* Define to prevent recursive inclusion -------------------------------------*/ 24 | #ifndef __SD_DISKIO_H 25 | #define __SD_DISKIO_H 26 | 27 | /* USER CODE BEGIN firstSection */ 28 | /* can be used to modify / undefine following code or add new definitions */ 29 | /* USER CODE END firstSection */ 30 | 31 | /* Includes ------------------------------------------------------------------*/ 32 | #include "bsp_driver_sd.h" 33 | /* Exported types ------------------------------------------------------------*/ 34 | /* Exported constants --------------------------------------------------------*/ 35 | /* Exported functions ------------------------------------------------------- */ 36 | extern const Diskio_drvTypeDef SD_Driver; 37 | 38 | /* USER CODE BEGIN lastSection */ 39 | /* can be used to modify / undefine previous code or add new definitions */ 40 | /* USER CODE END lastSection */ 41 | 42 | #endif /* __SD_DISKIO_H */ 43 | 44 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 45 | 46 | -------------------------------------------------------------------------------- /Code Project/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 | -------------------------------------------------------------------------------- /Code Project/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 0 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 | #endif // MAVLINK_H 35 | -------------------------------------------------------------------------------- /Code Project/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 "Tue Jul 24 2018" 11 | #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" 12 | #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 13 | 14 | #endif // MAVLINK_VERSION_H 15 | -------------------------------------------------------------------------------- /Code Project/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_ctlreq.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file usbd_req.h 4 | * @author MCD Application Team 5 | * @brief Header file for the usbd_req.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2015 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __USB_REQUEST_H 22 | #define __USB_REQUEST_H 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "usbd_def.h" 30 | 31 | 32 | /** @addtogroup STM32_USB_DEVICE_LIBRARY 33 | * @{ 34 | */ 35 | 36 | /** @defgroup USBD_REQ 37 | * @brief header file for the usbd_req.c file 38 | * @{ 39 | */ 40 | 41 | /** @defgroup USBD_REQ_Exported_Defines 42 | * @{ 43 | */ 44 | /** 45 | * @} 46 | */ 47 | 48 | 49 | /** @defgroup USBD_REQ_Exported_Types 50 | * @{ 51 | */ 52 | /** 53 | * @} 54 | */ 55 | 56 | 57 | 58 | /** @defgroup USBD_REQ_Exported_Macros 59 | * @{ 60 | */ 61 | /** 62 | * @} 63 | */ 64 | 65 | /** @defgroup USBD_REQ_Exported_Variables 66 | * @{ 67 | */ 68 | /** 69 | * @} 70 | */ 71 | 72 | /** @defgroup USBD_REQ_Exported_FunctionsPrototype 73 | * @{ 74 | */ 75 | 76 | USBD_StatusTypeDef USBD_StdDevReq(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 77 | USBD_StatusTypeDef USBD_StdItfReq(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 78 | USBD_StatusTypeDef USBD_StdEPReq(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 79 | 80 | void USBD_CtlError(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 81 | void USBD_ParseSetupRequest(USBD_SetupReqTypedef *req, uint8_t *pdata); 82 | void USBD_GetString(uint8_t *desc, uint8_t *unicode, uint16_t *len); 83 | 84 | /** 85 | * @} 86 | */ 87 | 88 | #ifdef __cplusplus 89 | } 90 | #endif 91 | 92 | #endif /* __USB_REQUEST_H */ 93 | 94 | /** 95 | * @} 96 | */ 97 | 98 | /** 99 | * @} 100 | */ 101 | 102 | 103 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 104 | -------------------------------------------------------------------------------- /Code Project/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_ioreq.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file usbd_ioreq.h 4 | * @author MCD Application Team 5 | * @brief Header file for the usbd_ioreq.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2015 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __USBD_IOREQ_H 22 | #define __USBD_IOREQ_H 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "usbd_def.h" 30 | #include "usbd_core.h" 31 | 32 | /** @addtogroup STM32_USB_DEVICE_LIBRARY 33 | * @{ 34 | */ 35 | 36 | /** @defgroup USBD_IOREQ 37 | * @brief header file for the usbd_ioreq.c file 38 | * @{ 39 | */ 40 | 41 | /** @defgroup USBD_IOREQ_Exported_Defines 42 | * @{ 43 | */ 44 | /** 45 | * @} 46 | */ 47 | 48 | 49 | /** @defgroup USBD_IOREQ_Exported_Types 50 | * @{ 51 | */ 52 | 53 | 54 | /** 55 | * @} 56 | */ 57 | 58 | 59 | 60 | /** @defgroup USBD_IOREQ_Exported_Macros 61 | * @{ 62 | */ 63 | 64 | /** 65 | * @} 66 | */ 67 | 68 | /** @defgroup USBD_IOREQ_Exported_Variables 69 | * @{ 70 | */ 71 | 72 | /** 73 | * @} 74 | */ 75 | 76 | /** @defgroup USBD_IOREQ_Exported_FunctionsPrototype 77 | * @{ 78 | */ 79 | 80 | USBD_StatusTypeDef USBD_CtlSendData(USBD_HandleTypeDef *pdev, 81 | uint8_t *pbuf, uint32_t len); 82 | 83 | USBD_StatusTypeDef USBD_CtlContinueSendData(USBD_HandleTypeDef *pdev, 84 | uint8_t *pbuf, uint32_t len); 85 | 86 | USBD_StatusTypeDef USBD_CtlPrepareRx(USBD_HandleTypeDef *pdev, 87 | uint8_t *pbuf, uint32_t len); 88 | 89 | USBD_StatusTypeDef USBD_CtlContinueRx(USBD_HandleTypeDef *pdev, 90 | uint8_t *pbuf, uint32_t len); 91 | 92 | USBD_StatusTypeDef USBD_CtlSendStatus(USBD_HandleTypeDef *pdev); 93 | USBD_StatusTypeDef USBD_CtlReceiveStatus(USBD_HandleTypeDef *pdev); 94 | 95 | uint32_t USBD_GetRxCount(USBD_HandleTypeDef *pdev, uint8_t ep_addr); 96 | 97 | /** 98 | * @} 99 | */ 100 | 101 | #ifdef __cplusplus 102 | } 103 | #endif 104 | 105 | #endif /* __USBD_IOREQ_H */ 106 | 107 | /** 108 | * @} 109 | */ 110 | 111 | /** 112 | * @} 113 | */ 114 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 115 | -------------------------------------------------------------------------------- /Code Project/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 function */ 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 | -------------------------------------------------------------------------------- /Code Project/Middlewares/Third_Party/FatFs/src/ff_gen_drv.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file ff_gen_drv.h 4 | * @author MCD Application Team 5 | * @brief Header for ff_gen_drv.c module. 6 | ***************************************************************************** 7 | * @attention 8 | * 9 | * Copyright (c) 2017 STMicroelectronics. All rights reserved. 10 | * 11 | * This software component is licensed by ST under BSD 3-Clause license, 12 | * the "License"; You may not use this file except in compliance with the 13 | * License. You may obtain a copy of the License at: 14 | * opensource.org/licenses/BSD-3-Clause 15 | * 16 | ****************************************************************************** 17 | **/ 18 | 19 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef __FF_GEN_DRV_H 21 | #define __FF_GEN_DRV_H 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "diskio.h" 29 | #include "ff.h" 30 | #include "stdint.h" 31 | 32 | 33 | /* Exported types ------------------------------------------------------------*/ 34 | 35 | /** 36 | * @brief Disk IO Driver structure definition 37 | */ 38 | typedef struct 39 | { 40 | DSTATUS (*disk_initialize) (BYTE); /*!< Initialize Disk Drive */ 41 | DSTATUS (*disk_status) (BYTE); /*!< Get Disk Status */ 42 | DRESULT (*disk_read) (BYTE, BYTE*, DWORD, UINT); /*!< Read Sector(s) */ 43 | #if _USE_WRITE == 1 44 | DRESULT (*disk_write) (BYTE, const BYTE*, DWORD, UINT); /*!< Write Sector(s) when _USE_WRITE = 0 */ 45 | #endif /* _USE_WRITE == 1 */ 46 | #if _USE_IOCTL == 1 47 | DRESULT (*disk_ioctl) (BYTE, BYTE, void*); /*!< I/O control operation when _USE_IOCTL = 1 */ 48 | #endif /* _USE_IOCTL == 1 */ 49 | 50 | }Diskio_drvTypeDef; 51 | 52 | /** 53 | * @brief Global Disk IO Drivers structure definition 54 | */ 55 | typedef struct 56 | { 57 | uint8_t is_initialized[_VOLUMES]; 58 | const Diskio_drvTypeDef *drv[_VOLUMES]; 59 | uint8_t lun[_VOLUMES]; 60 | volatile uint8_t nbr; 61 | 62 | }Disk_drvTypeDef; 63 | 64 | /* Exported constants --------------------------------------------------------*/ 65 | /* Exported macro ------------------------------------------------------------*/ 66 | /* Exported functions ------------------------------------------------------- */ 67 | uint8_t FATFS_LinkDriver(const Diskio_drvTypeDef *drv, char *path); 68 | uint8_t FATFS_UnLinkDriver(char *path); 69 | uint8_t FATFS_LinkDriverEx(const Diskio_drvTypeDef *drv, char *path, BYTE lun); 70 | uint8_t FATFS_UnLinkDriverEx(char *path, BYTE lun); 71 | uint8_t FATFS_GetAttachedDriversNbr(void); 72 | 73 | #ifdef __cplusplus 74 | } 75 | #endif 76 | 77 | #endif /* __FF_GEN_DRV_H */ 78 | 79 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 80 | 81 | -------------------------------------------------------------------------------- /Code Project/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 | typedef unsigned __int64 QWORD; 13 | 14 | 15 | #else /* Embedded platform */ 16 | 17 | /* These types MUST be 16-bit or 32-bit */ 18 | typedef int INT; 19 | typedef unsigned int UINT; 20 | 21 | /* This type MUST be 8-bit */ 22 | typedef unsigned char BYTE; 23 | 24 | /* These types MUST be 16-bit */ 25 | typedef short SHORT; 26 | typedef unsigned short WORD; 27 | typedef unsigned short WCHAR; 28 | 29 | /* These types MUST be 32-bit */ 30 | typedef long LONG; 31 | typedef unsigned long DWORD; 32 | 33 | /* This type MUST be 64-bit (Remove this for ANSI C (C89) compatibility) */ 34 | typedef unsigned long long QWORD; 35 | 36 | #endif 37 | 38 | #endif 39 | -------------------------------------------------------------------------------- /Code Project/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2/cmsis_os2.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/makermare/UAV-FlyingControlSystem-BlueSkyFlightControl/d35d104cc8a21090000b984fbafd00f08f8a0f3e/Code Project/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2/cmsis_os2.c -------------------------------------------------------------------------------- /Code Project/SRC/CONTROL/commandControl.c: -------------------------------------------------------------------------------- 1 | #include "commandControl.h" 2 | #include "flightStatus.h" 3 | #include "drv_uart.h" 4 | 5 | FLIGHT_COMMAND_t flightCommand; 6 | MOTION_COMMAND_t motionCommand; 7 | SERVO_COMMAND_t servoCommand; 8 | 9 | uint8_t CommandFeedbackBuffer[4]; 10 | 11 | void CommandInit(void) { 12 | CommandFeedbackBuffer[0] = 0xFE; 13 | CommandFeedbackBuffer[2] = 0xFE; 14 | CommandFeedbackBuffer[3] = 0xFE; 15 | 16 | CommandFeedback(COMMAND_STARTUP_CHECK); 17 | } 18 | 19 | void CommandDataDecode(uint8_t *raw) { 20 | //帧头帧尾校验 21 | if (raw[0] != 0xAA || raw[14] != 0xBB) { 22 | return; 23 | } 24 | 25 | // uint16_t checksum = 0; 26 | // for (uint8_t i = 0; i < 15; i++) { 27 | // checksum += raw[i]; 28 | // } 29 | // checksum &= 0x00FF; 30 | // 31 | // //和校验字节校验 32 | // if(checksum != raw[15]){ 33 | // return; 34 | // } 35 | 36 | // 飞行控制命令,控制角度和飞行速度 37 | if(raw[1] == 0x41){ 38 | flightCommand.commandRollTarget = (int16_t)(raw[2]|raw[3]<<8); 39 | flightCommand.commandPitchTarget = (int16_t)(raw[4]|raw[5]<<8); 40 | flightCommand.commandYawVelocityTarget = (int16_t)(raw[6]|raw[7]<<8); 41 | flightCommand.commandVelocityTargetX = (int16_t)(raw[8]|raw[9]<<8); 42 | flightCommand.commandVelocityTargetY = (int16_t)(raw[10]|raw[11]<<8); 43 | flightCommand.commandAltitudeTargetZ = (int16_t)(raw[12]|raw[13]<<8); 44 | } 45 | 46 | if(raw[1] == 0x51){ 47 | //不能同时起飞和降落 48 | if(raw[2] == 1 && raw[3] == 1){ 49 | return; 50 | } 51 | //不能同时解锁和上锁 52 | if(raw[4] == 1 && raw[5] == 1){ 53 | return; 54 | } 55 | 56 | motionCommand.autoTakeOffCommand = raw[2]; 57 | motionCommand.autoLandCommand = raw[3]; 58 | motionCommand.armCommand = raw[4]; 59 | motionCommand.disarmCommand = raw[5]; 60 | motionCommand.flyAroundRod = raw[6]; 61 | motionCommand.buzzerRing = raw[7]; 62 | } 63 | 64 | if(raw[1] == 0x61){ 65 | servoCommand.servo1Value = (int16_t)(raw[2]|raw[3]<<8); 66 | servoCommand.servo2Value = (int16_t)(raw[4]|raw[5]<<8); 67 | } 68 | } 69 | 70 | void CommandFeedback(uint8_t feedback) { 71 | CommandFeedbackBuffer[1] = feedback; 72 | //Uart_SendData(6, (uint8_t *) CommandFeedbackBuffer, 4); 73 | } -------------------------------------------------------------------------------- /Code Project/SRC/CONTROL/commandControl.h: -------------------------------------------------------------------------------- 1 | #ifndef _COMMANDCONTROL_H_ 2 | #define _COMMANDCONTROL_H_ 3 | 4 | #include "board.h" 5 | 6 | enum 7 | { 8 | COMMAND_RECEIVED = 0, 9 | FINISH_ARM_FEEDBACK, 10 | START_TAKEOFF_FEEDBACK, 11 | FINISH_TAKEOFF_FEEDBACK, 12 | FINISH_POSITION_HOLD, 13 | FINISH_MOVE_X_FEEDBACK, 14 | FINISH_MOVE_Y_FEEDBACK, 15 | FINISH_MOVE_Z_FEEDBACK, 16 | START_LAND_FEEDBACK, 17 | FINISH_LAND_FEEDBACK, 18 | FINISH_DISARM_FEEDBACK, 19 | 20 | COMMAND_STARTUP_CHECK 21 | }; 22 | 23 | typedef struct { 24 | float commandRollTarget; 25 | float commandPitchTarget; 26 | float commandYawVelocityTarget; 27 | 28 | float commandVelocityTargetX; 29 | float commandVelocityTargetY; 30 | float commandAltitudeTargetZ; 31 | } FLIGHT_COMMAND_t; 32 | 33 | typedef struct { 34 | uint8_t autoTakeOffCommand; 35 | uint8_t autoLandCommand; 36 | 37 | uint8_t armCommand; 38 | uint8_t disarmCommand; 39 | 40 | uint8_t flyAroundRod; 41 | 42 | uint8_t buzzerRing; 43 | } MOTION_COMMAND_t; 44 | 45 | typedef struct { 46 | int16_t servo1Value; 47 | int16_t servo2Value; 48 | } SERVO_COMMAND_t; 49 | 50 | extern FLIGHT_COMMAND_t flightCommand; 51 | extern MOTION_COMMAND_t motionCommand; 52 | extern SERVO_COMMAND_t servoCommand; 53 | 54 | void CommandInit(void); 55 | void CommandDataDecode(uint8_t *raw); 56 | 57 | void CommandFeedback(uint8_t feedback); 58 | 59 | #endif 60 | -------------------------------------------------------------------------------- /Code Project/SRC/CONTROL/flightControl.h: -------------------------------------------------------------------------------- 1 | #ifndef _FLIGHTCONTROL_H_ 2 | #define _FLIGHTCONTROL_H_ 3 | 4 | #include "mathTool.h" 5 | #include "pid.h" 6 | 7 | #define MAXANGLE 300 //最大飞行角度:30° 8 | #define MAXRCDATA 450 9 | 10 | enum 11 | { 12 | ROLL_INNER, 13 | PITCH_INNER, 14 | YAW_INNER, 15 | ROLL_OUTER, 16 | PITCH_OUTER, 17 | YAW_OUTER, 18 | VEL_X, 19 | VEL_Y, 20 | VEL_Z, 21 | POS_X, 22 | POS_Y, 23 | POS_Z, 24 | PIDNUM 25 | }; 26 | 27 | typedef struct 28 | { 29 | float roll; 30 | float pitch; 31 | float yaw; 32 | float throttle; 33 | } RCTARGET_t; 34 | 35 | typedef struct 36 | { 37 | PID_t pid[PIDNUM]; //PID参数结构体 38 | 39 | RCTARGET_t rcTarget; //摇杆控制量 40 | Vector3f_t angleLpf; 41 | 42 | Vector3f_t attInnerCtlValue; //姿态内环控制量 43 | float altInnerCtlValue; //高度内环控制量 44 | 45 | Vector3f_t attInnerTarget; //姿态内环(角速度)控制目标 46 | Vector3f_t attOuterTarget; //姿态外环(角度)控制目标 47 | Vector3f_t posInnerTarget; //位置内环(速度)控制目标 48 | Vector3f_t posOuterTarget; //位置外环(位置)控制目标 49 | 50 | Vector3f_t attInnerError; //姿态内环(角速度)控制误差 51 | Vector3f_t attOuterError; //姿态外环(角度)控制误差 52 | Vector3f_t posInnerError; //位置内环(速度)控制误差 53 | Vector3f_t posOuterError; //位置外环(位置)控制误差 54 | 55 | uint8_t altCtlFlag; //高度控制使能标志位 56 | uint8_t posCtlFlagX; //位置控制使能标志位 57 | uint8_t posCtlFlagY; //位置控制使能标志位 58 | uint8_t yawHoldFlag; //航向锁定控制使能标志位 59 | 60 | int16_t maxBrakeAngle; //最大刹车角度 61 | int16_t maxPosOuterCtl; //位置控制的最大输出 62 | int16_t maxAltOuterCtl; //高度控制的最大输出 63 | } FLIGHTCONTROL_t; 64 | 65 | void FlightControlInit(void); 66 | 67 | void SetRcTarget(RCTARGET_t rcTarget); 68 | void FlightControlInnerLoop(Vector3f_t gyro); 69 | void AttitudeOuterControl(void); 70 | void AltitudeOuterControl(void); 71 | void PositionInnerControl(void); 72 | void PositionOuterControl(void); 73 | 74 | void SetYawCtlTarget(float target); 75 | 76 | void SetAltInnerCtlTarget(float target); 77 | void SetAltOuterCtlTarget(float target); 78 | 79 | void SetPosInnerCtlTarget(Vector3f_t target); 80 | void SetPosInnerCtlTargetX(float targetX); 81 | void SetPosInnerCtlTargetY(float targetY); 82 | 83 | void SetPosOuterCtlTarget(Vector3f_t target); 84 | void SetPosOuterCtlTargetX(float target); 85 | void SetPosOuterCtlTargetY(float target); 86 | 87 | void SetAltCtlStatus(uint8_t status); 88 | void SetPosCtlStatusX(uint8_t status); 89 | void SetPosCtlStatusY(uint8_t status); 90 | void SetYawHoldStatus(uint8_t status); 91 | 92 | Vector3f_t GetAttInnerCtlError(void); 93 | Vector3f_t GetAttOuterCtlError(void); 94 | Vector3f_t GetPosInnerCtlError(void); 95 | Vector3f_t GetPosOuterCtlError(void); 96 | 97 | Vector3f_t GetAttInnerCtlTarget(void); 98 | Vector3f_t GetAttOuterCtlTarget(void); 99 | Vector3f_t GetPosInnerCtlTarget(void); 100 | Vector3f_t GetPosOuterCtlTarget(void); 101 | 102 | void FlightControlReset(void); 103 | PID_t FcGetPID(uint8_t id); 104 | void FcSetPID(uint8_t id, PID_t pid); 105 | bool PIDReadFromFlash(void); 106 | 107 | void SetMaxBrakeAngle(int16_t angle); 108 | void SetMaxPosOuterCtl(int16_t vel); 109 | void SetMaxAltOuterCtl(int16_t vel); 110 | 111 | #endif 112 | 113 | 114 | 115 | -------------------------------------------------------------------------------- /Code Project/SRC/CONTROL/missionControl.h: -------------------------------------------------------------------------------- 1 | #ifndef _MISSIONCONTROL_H_ 2 | #define _MISSIONCONTROL_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | enum 7 | { 8 | RTH_STEP_START = 0, 9 | RTH_STEP_TURN, 10 | RTH_STEP_CLIMB, 11 | RTH_STEP_FLIGHT, 12 | RTH_STEP_TURN_BACK, 13 | RTH_STEP_LOITER 14 | }; 15 | 16 | // 命令流程 17 | enum 18 | { 19 | WaitArm= 0, 20 | InTakeOff, 21 | FlightWithCommand, 22 | InLanding, 23 | WaitDisarm 24 | }; 25 | 26 | void MissionControl(void); 27 | 28 | #endif 29 | 30 | 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /Code Project/SRC/CONTROL/motor.h: -------------------------------------------------------------------------------- 1 | #ifndef _MOTOR_H_ 2 | #define _MOTOR_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | typedef struct 7 | { 8 | float throttle; //油门 9 | float roll; //横滚 10 | float pitch; //俯仰 11 | float yaw; //偏航 12 | } MOTOR_MIXER_t; 13 | 14 | typedef struct 15 | { 16 | int8_t motorNum; 17 | MOTOR_MIXER_t motorMixer[8]; 18 | } MOTOR_TYPE_t; 19 | 20 | void MotorInit(void); 21 | void MotorControl(int16_t roll, int16_t pitch, int16_t yaw, int16_t throttle); 22 | void EscCalibrateEnable(void); 23 | void MotorStop(void); 24 | int16_t* GetMotorValue(void); 25 | int8_t GetMotorNum(void); 26 | 27 | #endif 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | -------------------------------------------------------------------------------- /Code Project/SRC/CONTROL/rc.h: -------------------------------------------------------------------------------- 1 | #ifndef _RC_H_ 2 | #define _RC_H_ 3 | 4 | #include "mathTool.h" 5 | #include "board.h" 6 | 7 | enum 8 | { 9 | AUX1, 10 | AUX2, 11 | AUX3, 12 | AUX4, 13 | AUX5, 14 | AUX6, 15 | AUX7, 16 | AUX8, 17 | AUX9, 18 | AUX10, 19 | AUX11, 20 | AUX12 21 | }; 22 | 23 | enum 24 | { 25 | LOW, 26 | MID, 27 | HIGH 28 | }; 29 | 30 | enum 31 | { 32 | ROLL, 33 | PITCH, 34 | YAW, 35 | THROTTLE 36 | }; 37 | 38 | typedef struct 39 | { 40 | int16_t roll; //横滚 41 | int16_t pitch; //俯仰 42 | int16_t yaw; //偏航 43 | int16_t throttle; //油门 44 | } RCCOMMAND_t; 45 | 46 | void RcInit(void); 47 | void RcCheck(void); 48 | void RcDataUpdate(RCDATA_t data); 49 | RCDATA_t GetRcData(void); 50 | RCCOMMAND_t GetRcCommad(void); 51 | 52 | void FlightStatusUpdate(void); 53 | 54 | #endif 55 | 56 | 57 | 58 | -------------------------------------------------------------------------------- /Code Project/SRC/CONTROL/safeControl.h: -------------------------------------------------------------------------------- 1 | #ifndef _SAFECONTROL_H_ 2 | #define _SAFECONTROL_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | void SafeControl(void); 7 | 8 | #endif 9 | 10 | 11 | 12 | -------------------------------------------------------------------------------- /Code Project/SRC/CONTROL/userControl.h: -------------------------------------------------------------------------------- 1 | #ifndef _USERCONTROL_H_ 2 | #define _USERCONTROL_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | void UserControl(void); 7 | 8 | #endif 9 | 10 | -------------------------------------------------------------------------------- /Code Project/SRC/CONTROL/waypointControl.h: -------------------------------------------------------------------------------- 1 | #ifndef _WAYPOINTCONTROL_H_ 2 | #define _WAYPOINTCONTROL_H_ 3 | 4 | #include "mathTool.h" 5 | #include "mavlink.h" 6 | 7 | void WaypointControl(void); 8 | 9 | uint16_t GetWaypointCount(void); 10 | void SetWaypointCount(uint16_t count); 11 | uint16_t GetWaypointRecvCount(void); 12 | void SetWaypointRecvCount(uint16_t count); 13 | uint16_t GetWaypointSendCount(void); 14 | void SetWaypointSendCount(uint16_t count); 15 | 16 | void SetWaypointItem(uint16_t count, mavlink_mission_item_t item); 17 | void ClearAllWaypointItem(void); 18 | mavlink_mission_item_t GetWaypointItem(uint16_t count); 19 | 20 | #endif 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/board.h: -------------------------------------------------------------------------------- 1 | #ifndef __BOARD_H__ 2 | #define __BOARD_H__ 3 | 4 | #include "stm32h7xx.h" 5 | 6 | #include "stdbool.h" 7 | 8 | #if defined ( __GNUC__ ) 9 | #define __nop() asm("nop") 10 | #endif 11 | 12 | /********************************************************************************************************** 13 | *飞控软件版本 14 | **********************************************************************************************************/ 15 | #define SOFTWARE_VERSION_HIGH 0 16 | #define SOFTWARE_VERSION_MID 4 17 | #define SOFTWARE_VERSION_LOW 27 18 | 19 | /********************************************************************************************************** 20 | *飞控硬件类型 21 | **********************************************************************************************************/ 22 | enum { 23 | BOARD_BLUESKY_V3 = 1, 24 | BOARD_FUTURESKY 25 | }; 26 | 27 | /********************************************************************************************************** 28 | *定义硬件类型 29 | **********************************************************************************************************/ 30 | #define BLUESKY_V3 31 | 32 | //硬件配置头文件包含 33 | #ifdef BLUESKY_V3 34 | 35 | #include "boardConfigBlueSkyV3.h" 36 | 37 | #define BOARD_TYPE BOARD_BLUESKY_V3 38 | #endif 39 | 40 | typedef struct { 41 | int16_t roll; 42 | int16_t pitch; 43 | int16_t yaw; 44 | int16_t throttle; 45 | int16_t aux1; 46 | int16_t aux2; 47 | int16_t aux3; 48 | int16_t aux4; 49 | int16_t aux5; 50 | int16_t aux6; 51 | int16_t aux7; 52 | int16_t aux8; 53 | int16_t aux9; 54 | int16_t aux10; 55 | int16_t aux11; 56 | int16_t aux12; 57 | } RCDATA_t; 58 | 59 | enum { 60 | MPU6000, 61 | MPU6500, 62 | ICM20602, 63 | ICM20689, 64 | ICM20948 65 | }; 66 | 67 | enum { 68 | BMP280, 69 | MS5611, 70 | _2SMPB, 71 | LPS22HB, 72 | SPL06 73 | }; 74 | 75 | enum { 76 | BARO_USE_I2C, 77 | BARO_USE_SPI 78 | }; 79 | 80 | enum { 81 | HMC5883, 82 | QMC5883, 83 | IST8310, 84 | MMC3630, 85 | ICM20948_MAG 86 | }; 87 | 88 | enum { 89 | TFMINIPLUS, 90 | VL53Lxx //Not support now 91 | }; 92 | 93 | enum { 94 | LC302, 95 | PWM3901, //Not support now 96 | PX4FLOW 97 | }; 98 | 99 | enum { 100 | SBUS, 101 | PPM 102 | }; 103 | 104 | void BoardInit(void); 105 | 106 | void SoftDelayMs(uint32_t ms); 107 | 108 | void SoftDelayUs(uint32_t us); 109 | 110 | void OsDelayMs(uint32_t ms); 111 | 112 | uint64_t GetSysTimeUs(void); 113 | 114 | uint32_t GetSysTimeMs(void); 115 | 116 | #endif 117 | 118 | 119 | 120 | 121 | 122 | 123 | -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/drv_adc.c: -------------------------------------------------------------------------------- 1 | /********************************************************************************************************** 2 | 天穹飞控 —— 致力于打造中国最好的多旋翼开源飞控 3 | Github: github.com/loveuav/BlueSkyFlightControl 4 | 技术讨论:bbs.loveuav.com/forum-68-1.html 5 | * @文件 drv_adc.c 6 | * @说明 ADC驱动 7 | * @版本 V1.0 8 | * @作者 BlueSky 9 | * @网站 bbs.loveuav.com 10 | * @日期 2018.06 11 | **********************************************************************************************************/ 12 | #include "drv_adc.h" 13 | 14 | /********************************************************************************************************** 15 | *函 数 名: Adc_Init 16 | *功能说明: ADC初始化 17 | *形 参: 无 18 | *返 回 值: 无 19 | **********************************************************************************************************/ 20 | void Adc_Init(void) 21 | { 22 | MX_ADC1_Init(); 23 | MX_ADC2_Init(); 24 | 25 | if (HAL_ADCEx_Calibration_Start(&hadc1, ADC_CALIB_OFFSET, ADC_SINGLE_ENDED) != HAL_OK) { 26 | Error_Handler(); 27 | } 28 | 29 | if (HAL_ADCEx_Calibration_Start(&hadc2, ADC_CALIB_OFFSET, ADC_SINGLE_ENDED) != HAL_OK) { 30 | Error_Handler(); 31 | } 32 | 33 | if (HAL_ADC_Start(&hadc1) != HAL_OK) { 34 | Error_Handler(); 35 | } 36 | 37 | if (HAL_ADC_Start(&hadc2) != HAL_OK) { 38 | Error_Handler(); 39 | } 40 | } 41 | 42 | /********************************************************************************************************** 43 | *函 数 名: GetVoltageAdcValue 44 | *功能说明: 获取电压ADC采样值 45 | *形 参: 无 46 | *返 回 值: ADC采样值 47 | **********************************************************************************************************/ 48 | uint16_t GetVoltageAdcValue(void) 49 | { 50 | static uint16_t adcTemp; 51 | 52 | HAL_ADC_Start(&ADC_VOLTAGE); 53 | HAL_ADC_PollForConversion(&ADC_VOLTAGE, 1); 54 | adcTemp = HAL_ADC_GetValue(&ADC_VOLTAGE); 55 | 56 | return (adcTemp * 330 / 0xFFF); 57 | } 58 | 59 | /********************************************************************************************************** 60 | *函 数 名: GetCurrentAdcValue 61 | *功能说明: 获取电流ADC采样值 62 | *形 参: 无 63 | *返 回 值: ADC采样值 64 | **********************************************************************************************************/ 65 | uint16_t GetCurrentAdcValue(void) 66 | { 67 | static uint16_t adcTemp; 68 | 69 | HAL_ADC_Start(&ADC_CURRENT); 70 | HAL_ADC_PollForConversion(&ADC_CURRENT, 1); 71 | adcTemp = HAL_ADC_GetValue(&ADC_CURRENT); 72 | 73 | return (adcTemp * 330 / 0xFFF); 74 | } 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/drv_adc.h: -------------------------------------------------------------------------------- 1 | #ifndef __DRV_ADC_H__ 2 | #define __DRV_ADC_H__ 3 | 4 | #include "board.h" 5 | 6 | #include "adc.h" 7 | 8 | void Adc_Init(void); 9 | uint16_t GetVoltageAdcValue(void); 10 | uint16_t GetCurrentAdcValue(void); 11 | 12 | #endif 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/drv_flash.h: -------------------------------------------------------------------------------- 1 | #ifndef __DRV_FLASH_H__ 2 | #define __DRV_FLASH_H__ 3 | 4 | #include "board.h" 5 | 6 | uint8_t Flash_ReadByte(uint32_t start_addr, uint16_t cnt); 7 | 8 | bool Flash_WriteFLASHWORD(uint32_t dest, uint8_t *src, uint32_t length); 9 | 10 | #endif 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/drv_i2c.c: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Liuyufanlyf on 2021/05/07. 3 | // 4 | 5 | #include "drv_i2c.h" 6 | 7 | void I2C_Init() { 8 | MX_I2C1_Init(); 9 | MX_I2C2_Init(); 10 | MX_I2C4_Init(); 11 | } 12 | 13 | bool I2C_Single_Write(I2C_HandleTypeDef *device, uint8_t SlaveAddress, uint8_t REG_Address, uint8_t REG_data) { 14 | HAL_I2C_Mem_Write(device, SlaveAddress<<1, REG_Address, I2C_MEMADD_SIZE_8BIT, ®_data, 1, 1); 15 | }; 16 | 17 | uint8_t I2C_Single_Read(I2C_HandleTypeDef *device, uint8_t SlaveAddress, uint8_t REG_Address) { 18 | uint8_t temp; 19 | HAL_I2C_Mem_Read(device, SlaveAddress<<1, REG_Address, I2C_MEMADD_SIZE_8BIT, &temp, 1, 1); 20 | return temp; 21 | }; 22 | 23 | bool I2C_Multi_Read(I2C_HandleTypeDef *device, uint8_t SlaveAddress, uint8_t REG_Address, uint8_t *ptChar, uint8_t size) { 24 | HAL_I2C_Mem_Read(device, SlaveAddress<<1, REG_Address, I2C_MEMADD_SIZE_8BIT, ptChar, size, 1); 25 | }; 26 | -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/drv_i2c.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Liuyufanlyf on 2021/05/07. 3 | // 4 | 5 | #ifndef QUADCOPTER_DRV_I2C_H 6 | #define QUADCOPTER_DRV_I2C_H 7 | 8 | #include "board.h" 9 | 10 | #include "i2c.h" 11 | 12 | void I2C_Init(); 13 | bool I2C_Single_Write(I2C_HandleTypeDef* device, uint8_t SlaveAddress,uint8_t REG_Address,uint8_t REG_data); 14 | uint8_t I2C_Single_Read(I2C_HandleTypeDef* device, uint8_t SlaveAddress,uint8_t REG_Address); 15 | bool I2C_Multi_Read(I2C_HandleTypeDef* device, uint8_t SlaveAddress,uint8_t REG_Address,uint8_t * ptChar,uint8_t size); 16 | 17 | #endif //QUADCOPTER_DRV_I2C_H 18 | -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/drv_i2c_soft.h: -------------------------------------------------------------------------------- 1 | //#ifndef __DRV_I2C_SOFT_H__ 2 | //#define __DRV_I2C_SOFT_H__ 3 | // 4 | //#include "board.h" 5 | // 6 | //void Soft_I2c_Open(uint8_t deviceNum); 7 | //bool Soft_I2c_Single_Write(uint8_t deviceNum, uint8_t SlaveAddress,uint8_t REG_Address,uint8_t REG_data); 8 | //uint8_t Soft_I2C_Single_Read(uint8_t deviceNum, uint8_t SlaveAddress,uint8_t REG_Address); 9 | //bool Soft_I2C_Multi_Read(uint8_t deviceNum, uint8_t SlaveAddress,uint8_t REG_Address,uint8_t * ptChar,uint8_t size); 10 | // 11 | //#endif 12 | // 13 | // 14 | // 15 | -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/drv_ibus.c: -------------------------------------------------------------------------------- 1 | // 2 | // Created by 12484 on 2021/07/18. 3 | // 4 | 5 | #include "drv_ibus.h" 6 | #include "rc.h" 7 | 8 | uint8_t ibus_raw[32]; 9 | 10 | RCDATA_t ibusData; 11 | 12 | /********************************************************************************************************** 13 | *函 数 名: Ibus_Init 14 | *功能说明: ibus数据解析初始化 15 | *形 参: 无 16 | *返 回 值: 无 17 | **********************************************************************************************************/ 18 | void Ibus_Init(void) 19 | { 20 | if(SBUS_INV == 1) { 21 | HAL_GPIO_WritePin(SBUS_INV_GPIO, SBUS_INV_PIN, 1); 22 | } 23 | else 24 | HAL_GPIO_WritePin(SBUS_INV_GPIO, SBUS_INV_PIN, 0); 25 | } 26 | 27 | /********************************************************************************************************** 28 | *函 数 名: Ibus_Decode 29 | *功能说明: ibus协议解析 30 | *形 参: 输入数据 31 | *返 回 值: 无 32 | **********************************************************************************************************/ 33 | void Ibus_Decode(uint8_t data) 34 | { 35 | static uint32_t lastTime; 36 | static uint32_t dataCnt = 0; 37 | static uint8_t initFlag = 0; 38 | 39 | if(GetSysTimeMs() < 2000) 40 | return; 41 | 42 | uint32_t deltaT = GetSysTimeMs() - lastTime; 43 | lastTime = GetSysTimeMs(); 44 | 45 | //发送频率200Hz,间隔时间约4.7ms 46 | //数据间隔大于3ms则可以认为新的一帧开始了 47 | if(deltaT > 3) 48 | { 49 | dataCnt = 0; 50 | } 51 | 52 | //接收数据 53 | ibus_raw[dataCnt++] = data; 54 | 55 | //每帧数据长度为25 56 | if(dataCnt == 32) 57 | { 58 | //判断帧头是否正确 59 | if(ibus_raw[0] != 0x20 || ibus_raw[1] != 0x40) 60 | return; 61 | 62 | //每个通道数据占据11个字节,15-18通道的解析较为麻烦,暂时不做 63 | //转换摇杆数据量程为[1000:2000] 64 | ibusData.roll = ibus_raw[3] + ((ibus_raw[4]&0x0F)<<8); 65 | ibusData.pitch = ibus_raw[5] + ((ibus_raw[6]&0x0F)<<8); 66 | ibusData.throttle = ibus_raw[7] + ((ibus_raw[8]&0x0F)<<8); 67 | ibusData.yaw = ibus_raw[9] + ((ibus_raw[10]&0x0F)<<8); 68 | ibusData.aux1 = ibus_raw[11] + ((ibus_raw[12]&0x0F)<<8); 69 | ibusData.aux2 = ibus_raw[13] + ((ibus_raw[14]&0x0F)<<8); 70 | ibusData.aux3 = ibus_raw[15] + ((ibus_raw[16]&0x0F)<<8); 71 | ibusData.aux4 = ibus_raw[17] + ((ibus_raw[18]&0x0F)<<8); 72 | ibusData.aux5 = ibus_raw[19] + ((ibus_raw[20]&0x0F)<<8); 73 | ibusData.aux6 = ibus_raw[21] + ((ibus_raw[22]&0x0F)<<8); 74 | ibusData.aux7 = ibus_raw[23] + ((ibus_raw[23]&0x0F)<<8); 75 | ibusData.aux8 = ibus_raw[25] + ((ibus_raw[24]&0x0F)<<8); 76 | 77 | //一帧数据解析完成 78 | RcDataUpdate(ibusData); 79 | 80 | if(!initFlag) 81 | { 82 | initFlag = 1; 83 | } 84 | } 85 | } -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/drv_ibus.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by 12484 on 2021/07/18. 3 | // 4 | 5 | // 富斯ibus协议解析 6 | 7 | #include "board.h" 8 | 9 | void Ibus_Init(void); 10 | void Ibus_Decode(uint8_t data); -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/drv_pwm.h: -------------------------------------------------------------------------------- 1 | #ifndef __DRV_PWM_H__ 2 | #define __DRV_PWM_H__ 3 | 4 | #include "board.h" 5 | 6 | #include "tim.h" 7 | 8 | void PWM_Init(void); 9 | void TempControlPWMSet(int32_t pwmValue); 10 | void ServoControlPWMSet(uint8_t motor, int16_t pwmValue); 11 | void MotorPWMSet(uint8_t motor, uint16_t pwmValue); 12 | void BuzzerPWMSet(uint16_t pwmValue); 13 | 14 | #endif 15 | 16 | -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/drv_sbus.h: -------------------------------------------------------------------------------- 1 | #ifndef __DRV_SBUS_H__ 2 | #define __DRV_SBUS_H__ 3 | 4 | #include "board.h" 5 | 6 | #include "usart.h" 7 | 8 | typedef void (*RcDataCallback)(RCDATA_t data); 9 | 10 | void Sbus_Init(void); 11 | void Sbus_Decode(uint8_t data); 12 | void Sbus_SetRcDataCallback(RcDataCallback rcDataCallback); 13 | void Sbus_Disable(void); 14 | 15 | #endif 16 | 17 | -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/drv_spi.c: -------------------------------------------------------------------------------- 1 | /********************************************************************************************************** 2 | 天穹飞控 —— 致力于打造中国最好的多旋翼开源飞控 3 | Github: github.com/loveuav/BlueSkyFlightControl 4 | 技术讨论:bbs.loveuav.com/forum-68-1.html 5 | * @文件 drv_spi.c 6 | * @说明 SPI驱动 7 | * @版本 V1.0.1 8 | * @作者 BlueSky 9 | * @网站 bbs.loveuav.com 10 | * @日期 2018.05 11 | **********************************************************************************************************/ 12 | #include "drv_spi.h" 13 | 14 | void SPI_Init(void) 15 | { 16 | MX_SPI1_Init(); 17 | MX_SPI2_Init(); 18 | MX_SPI4_Init(); 19 | MX_SPI6_Init(); 20 | } 21 | 22 | /********************************************************************************************************** 23 | *函 数 名: SPI_GyroEnable 24 | *功能说明: 陀螺仪CS脚使能 25 | *形 参: 无 26 | *返 回 值: 无 27 | **********************************************************************************************************/ 28 | void SPI_GyroEnable(void) 29 | { 30 | HAL_GPIO_WritePin(GYRO_CS_GPIO, GYRO_CS_PIN, 0); 31 | } 32 | 33 | /********************************************************************************************************** 34 | *函 数 名: SPI_GyroDisable 35 | *功能说明: 陀螺仪CS脚失能 36 | *形 参: 无 37 | *返 回 值: 无 38 | **********************************************************************************************************/ 39 | void SPI_GyroDisable(void) 40 | { 41 | HAL_GPIO_WritePin(GYRO_CS_GPIO, GYRO_CS_PIN, 1); 42 | } 43 | 44 | /********************************************************************************************************** 45 | *函 数 名: SPI_GyroSingleWrite 46 | *功能说明: 陀螺仪单个寄存器写入 47 | *形 参: 寄存器地址 写入值 48 | *返 回 值: 无 49 | **********************************************************************************************************/ 50 | void SPI_GyroSingleWrite(uint8_t reg, uint8_t value) 51 | { 52 | SPI_GyroEnable(); 53 | HAL_SPI_Transmit(&GYRO_SPI, ®, 1, 10); 54 | HAL_SPI_Transmit(&GYRO_SPI, &value, 1, 10); 55 | SPI_GyroDisable(); 56 | } 57 | 58 | /********************************************************************************************************** 59 | *函 数 名: SPI_GyroMultiRead 60 | *功能说明: 陀螺仪多个寄存器读出 61 | *形 参: 寄存器地址 读出缓冲区 读出长度 62 | *返 回 值: 无 63 | **********************************************************************************************************/ 64 | void SPI_GyroMultiRead(uint8_t reg, uint8_t *data, uint8_t length) 65 | { 66 | reg = reg|0x80; 67 | SPI_GyroEnable(); 68 | HAL_SPI_Transmit(&GYRO_SPI, (®), 1, 10); 69 | HAL_SPI_Receive(&GYRO_SPI, data, length, HAL_MAX_DELAY); 70 | SPI_GyroDisable(); 71 | } 72 | -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/drv_spi.h: -------------------------------------------------------------------------------- 1 | #ifndef __DRV_SPI_H__ 2 | #define __DRV_SPI_H__ 3 | 4 | #include "board.h" 5 | 6 | #include "spi.h" 7 | 8 | void SPI_Init(void); 9 | 10 | void SPI_GyroSingleWrite(uint8_t reg, uint8_t value); 11 | void SPI_GyroMultiRead(uint8_t reg,uint8_t *data, uint8_t length); 12 | void Spi_BaroSingleWrite(uint8_t reg, uint8_t value); 13 | void Spi_BaroMultiRead(uint8_t reg,uint8_t *data, uint8_t length); 14 | 15 | #endif 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/drv_uart.h: -------------------------------------------------------------------------------- 1 | #ifndef _DRV_UART_H 2 | #define _DRV_UART_H 3 | 4 | #include "board.h" 5 | 6 | #include "usart.h" 7 | 8 | void Uart_Init(); 9 | void Uart_SendData(uint8_t deviceNum, uint8_t *DataToSend,uint8_t length); 10 | 11 | #endif 12 | -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/drv_usb.c: -------------------------------------------------------------------------------- 1 | /********************************************************************************************************** 2 | 天穹飞控 —— 致力于打造中国最好的多旋翼开源飞控 3 | Github: github.com/loveuav/BlueSkyFlightControl 4 | 技术讨论:bbs.loveuav.com/forum-68-1.html 5 | * @文件 drv_usb.c 6 | * @说明 usb转串口驱动 7 | * @版本 V1.2 8 | * @作者 BlueSky 9 | * @网站 bbs.loveuav.com 10 | * @日期 2018.07 11 | **********************************************************************************************************/ 12 | #include "drv_usb.h" 13 | #include "usbd_cdc_if.h" 14 | 15 | /********************************************************************************************************** 16 | *函 数 名: Usb_Init 17 | *功能说明: USB驱动初始化 18 | *形 参: 无 19 | *返 回 值: 无 20 | **********************************************************************************************************/ 21 | void Usb_Init(void) 22 | { 23 | // Has been inited in freertos.c 24 | //MX_USB_DEVICE_Init(); 25 | } 26 | 27 | /********************************************************************************************************** 28 | *函 数 名: Usb_Send 29 | *功能说明: USB发送数据 30 | *形 参: 发送数据缓冲区指针 数据长度 31 | *返 回 值: 无 32 | **********************************************************************************************************/ 33 | void Usb_Send(uint8_t *dataToSend, uint8_t length) 34 | { 35 | CDC_Transmit_FS(dataToSend, length); 36 | } 37 | -------------------------------------------------------------------------------- /Code Project/SRC/DRIVER/drv_usb.h: -------------------------------------------------------------------------------- 1 | #ifndef _DRV_USB_H 2 | #define _DRV_USB_H 3 | 4 | #include "board.h" 5 | 6 | void Usb_Init(void); 7 | void Usb_Send(uint8_t *dataToSend, uint8_t length); 8 | 9 | #endif 10 | -------------------------------------------------------------------------------- /Code Project/SRC/LOG/logger.h: -------------------------------------------------------------------------------- 1 | #ifndef _LOGGER_H_ 2 | #define _LOGGER_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | #define LOG_RATE 100 //日志记录频率 单位:Hz 7 | 8 | void LoggerInit(void); 9 | void LoggerLoop(void); 10 | void LoggerWrite(void *data, uint16_t size); 11 | 12 | #endif 13 | 14 | 15 | -------------------------------------------------------------------------------- /Code Project/SRC/LOG/ulog.h: -------------------------------------------------------------------------------- 1 | #ifndef _ULOG_H_ 2 | #define _ULOG_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | enum ULogMessageType 7 | { 8 | FORMAT = 'F', 9 | DATA = 'D', 10 | INFO = 'I', 11 | INFO_MULTIPLE = 'M', 12 | PARAMETER = 'P', 13 | ADD_LOGGED_MSG = 'A', 14 | REMOVE_LOGGED_MSG = 'R', 15 | SYNC = 'S', 16 | DROPOUT = 'O', 17 | LOGGING = 'L', 18 | FLAG_BITS = 'B', 19 | }; 20 | 21 | #pragma pack (1) 22 | 23 | typedef struct 24 | { 25 | uint8_t magic[8]; 26 | uint64_t timestamp; 27 | } ulog_file_header_s; 28 | 29 | #define ULOG_MSG_HEADER_LEN 3 30 | typedef struct 31 | { 32 | uint16_t msg_size; 33 | uint8_t msg_type; 34 | } ulog_message_header_s; 35 | 36 | typedef struct 37 | { 38 | uint16_t msg_size; 39 | uint8_t msg_type; 40 | char format[2096]; 41 | } ulog_message_format_s; 42 | 43 | typedef struct 44 | { 45 | uint16_t msg_size; 46 | uint8_t msg_type; 47 | uint8_t multi_id; 48 | uint16_t msg_id; 49 | char message_name[255]; 50 | } ulog_message_add_logged_s; 51 | 52 | typedef struct { 53 | uint16_t msg_size; 54 | uint8_t msg_type; 55 | uint16_t msg_id; 56 | } ulog_message_remove_logged_s; 57 | 58 | typedef struct 59 | { 60 | uint16_t msg_size; 61 | uint8_t msg_type; 62 | uint8_t sync_magic[8]; 63 | } ulog_message_sync_s; 64 | 65 | typedef struct 66 | { 67 | uint16_t msg_size; 68 | uint8_t msg_type; 69 | uint16_t duration; 70 | } ulog_message_dropout_s; 71 | 72 | typedef struct 73 | { 74 | uint16_t msg_size; 75 | uint8_t msg_type; 76 | uint16_t msg_id; 77 | } ulog_message_data_header_s; 78 | 79 | typedef struct 80 | { 81 | uint16_t msg_size; 82 | uint8_t msg_type; 83 | uint8_t key_len; 84 | char key[255]; 85 | } ulog_message_info_header_s; 86 | 87 | typedef struct 88 | { 89 | uint16_t msg_size; 90 | uint8_t msg_type ; 91 | uint8_t is_continued; 92 | uint8_t key_len; 93 | char key[255]; 94 | } ulog_message_info_multiple_header_s; 95 | 96 | typedef struct 97 | { 98 | uint16_t msg_size; 99 | uint8_t msg_type; 100 | uint8_t log_level; 101 | uint64_t timestamp; 102 | char message[128]; 103 | } ulog_message_logging_s; 104 | 105 | typedef struct 106 | { 107 | uint16_t msg_size; 108 | uint8_t msg_type; 109 | uint8_t key_len; 110 | char key[255]; 111 | } ulog_message_parameter_header_s; 112 | 113 | 114 | #define ULOG_INCOMPAT_FLAG0_DATA_APPENDED_MASK (1<<0) 115 | 116 | typedef struct 117 | { 118 | uint16_t msg_size; 119 | uint8_t msg_type; 120 | uint8_t compat_flags[8]; 121 | uint8_t incompat_flags[8]; 122 | uint64_t appended_offsets[3]; 123 | } ulog_message_flag_bits_s; 124 | 125 | typedef struct 126 | { 127 | char* data_type; 128 | char* data_name; 129 | } ULOG_FORMAT_t; 130 | 131 | #pragma pack () 132 | 133 | void UlogWriteHeader(void); 134 | void UlogWriteFlag(void); 135 | void UlogWriteFormat(char* formatType, ULOG_FORMAT_t* ulog_format, int16_t dataNum); 136 | void UlogWriteAddLogged(char* logType, uint8_t msg_id); 137 | 138 | void UlogWriteData_Flight(void); 139 | void UlogWriteData_GPS(void); 140 | 141 | #endif 142 | 143 | 144 | -------------------------------------------------------------------------------- /Code Project/SRC/LOG/ulog_data.h: -------------------------------------------------------------------------------- 1 | #ifndef _ULOG_DATA_H_ 2 | #define _ULOG_DATA_H_ 3 | 4 | #include "mathTool.h" 5 | #include "ulog.h" 6 | 7 | #define ULOG_DATA_FLIGHT_NUM 18 8 | #define ULOG_DATA_GPS_NUM 14 9 | 10 | #define ULOG_DATA_FLIGHT_ID 0 11 | #define ULOG_DATA_GPS_ID 1 12 | 13 | typedef struct 14 | { 15 | uint64_t timestamp; 16 | int16_t roll_rate; 17 | int16_t pitch_rate; 18 | int16_t yaw_rate; 19 | int16_t roll_rate_sp; 20 | int16_t pitch_rate_sp; 21 | int16_t yaw_rate_sp; 22 | int16_t roll; 23 | int16_t pitch; 24 | int16_t yaw; 25 | int16_t roll_sp; 26 | int16_t pitch_sp; 27 | int16_t yaw_sp; 28 | int16_t accel[3]; 29 | int16_t velocity[3]; 30 | int16_t velocity_sp[3]; 31 | int32_t position[3]; 32 | int32_t position_sp[3]; 33 | } ULOG_DATA_FLIGHT_t; 34 | 35 | typedef struct 36 | { 37 | uint64_t timestamp; 38 | int32_t latitude; //纬度 39 | int32_t longitude; //经度 40 | int32_t altitude; //高度 41 | int32_t velN; //北向速度 42 | int32_t velE; //东向速度 43 | int32_t velD; //天向速度 44 | int16_t heading; //航向 45 | int16_t hAcc; //水平定位精度 46 | int16_t vAcc; //垂直定位精度 47 | int16_t sAcc; //速度精度 48 | int16_t cAcc; //航向精度 49 | uint8_t fixStatus; //定位状态 50 | uint8_t numSV; //卫星数量 51 | } ULOG_DATA_GPS_t; 52 | 53 | extern ULOG_FORMAT_t ulog_data_flight[ULOG_DATA_FLIGHT_NUM]; 54 | extern ULOG_FORMAT_t ulog_data_gps[ULOG_DATA_GPS_NUM]; 55 | 56 | #endif 57 | 58 | 59 | -------------------------------------------------------------------------------- /Code Project/SRC/MATH/LevenbergMarquardt.h: -------------------------------------------------------------------------------- 1 | #ifndef _LEVENBERGMARQUARDT_H 2 | #define _LEVENBERGMARQUARDT_H 3 | 4 | #include "mathTool.h" 5 | 6 | void LevenbergMarquardt(Vector3f_t inputData[6], Vector3f_t* offset, Vector3f_t* scale, float initBeta[6], float length); 7 | 8 | #endif 9 | -------------------------------------------------------------------------------- /Code Project/SRC/MATH/declination.h: -------------------------------------------------------------------------------- 1 | #ifndef _DECLINATION_H 2 | #define _DECLINATION_H 3 | 4 | #include "mathTool.h" 5 | 6 | float CompassGetDeclination(float lat, float lon); 7 | 8 | #endif 9 | 10 | -------------------------------------------------------------------------------- /Code Project/SRC/MATH/kalman3.h: -------------------------------------------------------------------------------- 1 | #ifndef _KALMAN3_H_ 2 | #define _KALMAN3_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | typedef struct { 7 | //状态矩阵 8 | Vector3f_t state; 9 | //滑动窗口大小 10 | int16_t slidWindowSize; 11 | //状态滑动窗口 12 | Vector3f_t* statusSlidWindow; 13 | //观测信号相位补偿值 14 | Vector3i_t fuseDelay; 15 | //残差矩阵 16 | Vector3f_t residual; 17 | //状态转移矩阵 18 | float f[9]; 19 | //状态转移矩阵的转置 20 | float f_t[9]; 21 | //观测映射矩阵 22 | float h[9]; 23 | //观测映射矩阵的转置 24 | float h_t[9]; 25 | //控制输入矩阵 26 | float b[9]; 27 | //卡尔曼增益矩阵 28 | float gain[9]; 29 | //误差协方差矩阵 30 | float covariance[9]; 31 | //过程噪声协方差矩阵 32 | float q[9]; 33 | //测量噪声协方差矩阵 34 | float r[9]; 35 | } Kalman_t; 36 | 37 | void KalmanUpdate(Kalman_t* kalman, Vector3f_t input, Vector3f_t observe, bool flag); 38 | 39 | void KalmanStateTransMatSet(Kalman_t* kalman, float* f); 40 | void KalmanObserveMapMatSet(Kalman_t* kalman, float* h); 41 | void KalmanCovarianceMatSet(Kalman_t* kalman, float* p); 42 | void KalmanQMatSet(Kalman_t* kalman, float* q); 43 | void KalmanRMatSet(Kalman_t* kalman, float* r); 44 | void KalmanBMatSet(Kalman_t* kalman, float* b); 45 | 46 | #endif 47 | -------------------------------------------------------------------------------- /Code Project/SRC/MATH/kalmanVel.h: -------------------------------------------------------------------------------- 1 | #ifndef _KALMANVEL_H_ 2 | #define _KALMANVEL_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | typedef struct { 7 | //状态矩阵 8 | //状态量为:x轴速度 y轴速度 z轴速度 x轴加速度bias y轴加速度bias z轴加速度bias 9 | float state[6]; 10 | //滑动窗口大小 11 | int16_t slidWindowSize; 12 | //状态滑动窗口 13 | Vector3f_t* stateSlidWindow; 14 | //观测信号相位补偿值 15 | int16_t fuseDelay[6]; 16 | //残差矩阵 17 | float residual[6]; 18 | //状态转移矩阵 19 | float f[6][6]; 20 | //状态转移矩阵的转置 21 | float f_t[6][6]; 22 | //观测映射矩阵 23 | float h[6][6]; 24 | //观测映射矩阵的转置 25 | float h_t[6][6]; 26 | //控制输入矩阵 27 | float b[6][6]; 28 | //卡尔曼增益矩阵 29 | float gain[6][6]; 30 | //误差协方差矩阵 31 | float covariance[6][6]; 32 | //过程噪声协方差矩阵 33 | float q[6][6]; 34 | //测量噪声协方差矩阵 35 | float r[6][6]; 36 | } KalmanVel_t; 37 | 38 | void KalmanVelUpdate(KalmanVel_t* kalman, Vector3f_t* velocity, Vector3f_t* bias, Vector3f_t accel, 39 | float observe[6], float deltaT, bool fuseFlag); 40 | 41 | void KalmanVelStateTransMatSet(KalmanVel_t* kalman, float f[6][6]); 42 | void KalmanVelObserveMapMatSet(KalmanVel_t* kalman, float h[6][6]); 43 | void KalmanVelCovarianceMatSet(KalmanVel_t* kalman, float p[6][6]); 44 | void KalmanVelQMatSet(KalmanVel_t* kalman, float q[6][6]); 45 | void KalmanVelRMatSet(KalmanVel_t* kalman, float r[6][6]); 46 | void KalmanVelBMatSet(KalmanVel_t* kalman, float b[6][6]); 47 | 48 | void KalmanVelUseMeasurement(KalmanVel_t* kalman, uint8_t num, bool flag); 49 | 50 | #endif 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | -------------------------------------------------------------------------------- /Code Project/SRC/MATH/lowPassFilter.c: -------------------------------------------------------------------------------- 1 | /********************************************************************************************************** 2 | 天穹飞控 —— 致力于打造中国最好的多旋翼开源飞控 3 | Github: github.com/loveuav/BlueSkyFlightControl 4 | 技术讨论:bbs.loveuav.com/forum-68-1.html 5 | * @文件 lowPassFilter.c 6 | * @说明 低通滤波器 7 | * @版本 V1.1 8 | * @作者 BlueSky 9 | * @网站 bbs.loveuav.com 10 | * @日期 2018.07 11 | **********************************************************************************************************/ 12 | #include "lowPassFilter.h" 13 | 14 | /********************************************************************************************************** 15 | *函 数 名: LowPassFilter1st 16 | *功能说明: 一阶低通滤波器 17 | *形 参: 数据指针 新数据 滤波系数(新数据权重) 18 | *返 回 值: 无 19 | **********************************************************************************************************/ 20 | void LowPassFilter1st(Vector3f_t* data, Vector3f_t newData, float coff) 21 | { 22 | data->x = data->x * (1 - coff) + newData.x * coff; 23 | data->y = data->y * (1 - coff) + newData.y * coff; 24 | data->z = data->z * (1 - coff) + newData.z * coff; 25 | } 26 | 27 | /********************************************************************************************************** 28 | *函 数 名: LowPassFilter2ndFactorCal 29 | *功能说明: 二阶IIR低通滤波器系数计算,该滤波器由二阶模拟低通滤波电路数字化推导而来 30 | *形 参: 滤波器运行频率 截止频率 滤波器结构体指针 31 | *返 回 值: 无 32 | **********************************************************************************************************/ 33 | void LowPassFilter2ndFactorCal(float deltaT, float Fcut, LPF2ndData_t* lpf_data) 34 | { 35 | float a = 1 / (2 * M_PI * Fcut * deltaT); 36 | lpf_data->b0 = 1 / (a*a + 3*a + 1); 37 | lpf_data->a1 = (2*a*a + 3*a) / (a*a + 3*a + 1); 38 | lpf_data->a2 = (a*a) / (a*a + 3*a + 1); 39 | } 40 | 41 | /********************************************************************************************************** 42 | *函 数 名: LowPassFilter2nd 43 | *功能说明: 二阶IIR低通滤波器过程实现 44 | *形 参: 滤波器结构体指针 原始数据 45 | *返 回 值: 经过滤波的数据 46 | **********************************************************************************************************/ 47 | Vector3f_t LowPassFilter2nd(LPF2ndData_t* lpf_2nd, Vector3f_t rawData) 48 | { 49 | Vector3f_t lpf_2nd_data; 50 | 51 | lpf_2nd_data.x = rawData.x * lpf_2nd->b0 + lpf_2nd->lastout.x * lpf_2nd->a1 - lpf_2nd->preout.x * lpf_2nd->a2; 52 | lpf_2nd_data.y = rawData.y * lpf_2nd->b0 + lpf_2nd->lastout.y * lpf_2nd->a1 - lpf_2nd->preout.y * lpf_2nd->a2; 53 | lpf_2nd_data.z = rawData.z * lpf_2nd->b0 + lpf_2nd->lastout.z * lpf_2nd->a1 - lpf_2nd->preout.z * lpf_2nd->a2; 54 | 55 | lpf_2nd->preout.x = lpf_2nd->lastout.x; 56 | lpf_2nd->preout.y = lpf_2nd->lastout.y; 57 | lpf_2nd->preout.z = lpf_2nd->lastout.z; 58 | 59 | lpf_2nd->lastout.x = lpf_2nd_data.x; 60 | lpf_2nd->lastout.y = lpf_2nd_data.y; 61 | lpf_2nd->lastout.z = lpf_2nd_data.z; 62 | 63 | return lpf_2nd_data; 64 | } 65 | 66 | /********************************************************************************************************** 67 | *函 数 名: LinearComplementaryFilter 68 | *功能说明: 光流速度和加速度计加速度的一阶后向差分线性互补滤波,用于求取地理坐标系xy平面的速度,使用前确保坐标系一致 69 | *形 参: 时间常数 采样时间 xy轴加速度计的值(地理坐标系) xy轴光流速度(地理坐标系) xy轴速度(地理坐标系) 70 | *返 回 值: 经过滤波的x,y速度 71 | **********************************************************************************************************/ 72 | void LinearComplementaryFilter(float tao, float samplingtime, float acc_x, float acc_y, float v_opt_x, float v_opt_y, 73 | float *v_x, float *v_y) { 74 | *v_x = tao / (tao + samplingtime) * (*v_x + samplingtime * acc_x) + samplingtime / (tao + samplingtime) * v_opt_x; 75 | *v_y = tao / (tao + samplingtime) * (*v_y + samplingtime * acc_y) + samplingtime / (tao + samplingtime) * v_opt_y; 76 | } 77 | 78 | 79 | 80 | 81 | -------------------------------------------------------------------------------- /Code Project/SRC/MATH/lowPassFilter.h: -------------------------------------------------------------------------------- 1 | #ifndef _LOWPASSFILTER_H_ 2 | #define _LOWPASSFILTER_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | typedef struct 7 | { 8 | float b0; 9 | float a1; 10 | float a2; 11 | Vector3f_t preout; 12 | Vector3f_t lastout; 13 | } LPF2ndData_t; 14 | 15 | void LowPassFilter1st(Vector3f_t* data, Vector3f_t newData, float coff); 16 | void LowPassFilter2ndFactorCal(float deltaT, float Fcut, LPF2ndData_t* lpf_data); 17 | Vector3f_t LowPassFilter2nd(LPF2ndData_t* lpf_2nd, Vector3f_t rawData); 18 | void LinearComplementaryFilter(float tao, float samplingtime, float acc_x, float acc_y, float v_opt_x, float v_opt_y, 19 | float *v_x, float *v_y); 20 | 21 | 22 | #endif 23 | 24 | 25 | -------------------------------------------------------------------------------- /Code Project/SRC/MATH/mathTool.h: -------------------------------------------------------------------------------- 1 | #ifndef __MATHTOOL_H__ 2 | #define __MATHTOOL_H__ 3 | 4 | #include 5 | #include 6 | #include "stdbool.h" 7 | #include 8 | 9 | #include "vector3.h" 10 | 11 | #define min(a, b) ((a) < (b) ? (a) : (b)) 12 | #define max(a, b) ((a) > (b) ? (a) : (b)) 13 | #define abs(x) ((x) > 0 ? (x) : -(x)) 14 | 15 | //#define M_PI 3.141592653f //圆周率 16 | #define DEG_TO_RAD 0.01745329f //角度转弧度 17 | #define RAD_TO_DEG 57.29577951f //弧度转角度 18 | 19 | #define EARTH_RADIUS 6371.004f //km 20 | #define GRAVITY_ACCEL 9.8f //重力加速度 单位:m/s^2 21 | 22 | #define HALF_SQRT_2 0.70710678118654757f //根号2的值 23 | 24 | float SafeArcsin(float v); 25 | float ConstrainFloat(float amt, float low, float high); 26 | int16_t ConstrainInt16(int16_t amt, int16_t low, int16_t high); 27 | uint16_t ConstrainUint16(uint16_t amt, uint16_t low, uint16_t high); 28 | int32_t ConstrainInt32(int32_t amt, int32_t low, int32_t high); 29 | 30 | int32_t ApplyDeadbandInt(int32_t value, int32_t deadband); 31 | float ApplyDeadbandFloat(float value, float deadband); 32 | 33 | float Radians(float deg); 34 | float Degrees(float rad); 35 | 36 | float Sq(float v); 37 | float Pythagorous2(float a, float b); 38 | float Pythagorous3(float a, float b, float c); 39 | float Pythagorous4(float a, float b, float c, float d); 40 | 41 | float WrapDegree360(float angle); 42 | 43 | int32_t GetRandom(void); 44 | 45 | #endif 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | -------------------------------------------------------------------------------- /Code Project/SRC/MATH/matrix3.h: -------------------------------------------------------------------------------- 1 | #ifndef _MATRIX3_H_ 2 | #define _MATRIX3_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | void Matrix3_Add(float* a,float* b,float* c); 7 | void Matrix3_Sub(float* a,float* b,float* c); 8 | void Matrix3_Mul(float* a,float* b,float* c); 9 | void Matrix3_Copy(float* a, float* b); 10 | void Matrix3_Tran(float* a, float* b); 11 | void Matrix3_Det(float* a,float* b); 12 | 13 | #endif 14 | -------------------------------------------------------------------------------- /Code Project/SRC/MATH/matrix6.h: -------------------------------------------------------------------------------- 1 | #ifndef _MATRIX6_H_ 2 | #define _MATRIX6_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | void Matrix6_Add(float a[6][6], float b[6][6], float c[6][6]); 7 | void Matrix6_Sub(float a[6][6], float b[6][6], float c[6][6]); 8 | void Matrix6_Mul(float a[6][6], float b[6][6], float c[6][6]); 9 | void Matrix6_Copy(float a[6][6], float b[6][6]); 10 | void Matrix6_Tran(float a[6][6], float b[6][6]); 11 | bool Matrix6_Det(float a[6][6], float b[6][6]); 12 | 13 | void Vector6f_Add(float v1[6], float v2[6], float v3[6]); 14 | void Vector6f_Sub(float v1[6], float v2[6], float v3[6]); 15 | 16 | void Matrix6MulVector6(float m[6][6], float v[6], float result[6]); 17 | 18 | #endif 19 | 20 | -------------------------------------------------------------------------------- /Code Project/SRC/MATH/pid.h: -------------------------------------------------------------------------------- 1 | #ifndef _PID_H 2 | #define _PID_H 3 | 4 | #include "mathTool.h" 5 | 6 | typedef struct 7 | { 8 | float kP; 9 | float kI; 10 | float kD; 11 | 12 | float imax; 13 | float integrator; 14 | float lastError; 15 | float lastDerivative; 16 | float dFilter; 17 | } PID_t; 18 | 19 | float PID_GetP(PID_t* pid, float error); 20 | float PID_GetI(PID_t* pid, float error, float dt); 21 | void PID_ResetI(PID_t* pid); 22 | float PID_GetD(PID_t* pid, float error, float dt); 23 | float PID_GetPI(PID_t* pid, float error, float dt); 24 | float PID_GetPID(PID_t* pid, float error, float dt); 25 | void PID_SetParam(PID_t* pid, float p, float i, float d, float imaxval, float dCutFreq) ; 26 | 27 | #endif 28 | 29 | -------------------------------------------------------------------------------- /Code Project/SRC/MATH/quaternion.h: -------------------------------------------------------------------------------- 1 | #ifndef __QUATERNION_H__ 2 | #define __QUATERNION_H__ 3 | 4 | #include "mathTool.h" 5 | 6 | void EulerAngleToQuaternion(Vector3f_t angle, float q[4]); 7 | void QuaternionToDCM(float q[4], float dcM[9]); 8 | void QuaternionToDCM_T(float q[4], float dcM[9]); 9 | Vector3f_t QuaternionRotateToEarthFrame(float q[4], Vector3f_t vector); 10 | Vector3f_t QuaternionRotateToBodyFrame(float q[4], Vector3f_t vector); 11 | void QuaternionToEulerAngle(float q[4], Vector3f_t* angle); 12 | void QuaternionNormalize(float q[4]); 13 | 14 | #endif 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /Code Project/SRC/MATH/rotation.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROTATION_H 2 | #define _ROTATION_H 3 | 4 | #include "mathTool.h" 5 | 6 | enum Rotation 7 | { 8 | ROTATION_NONE = 0, 9 | ROTATION_YAW_45 = 1, 10 | ROTATION_YAW_90 = 2, 11 | ROTATION_YAW_135 = 3, 12 | ROTATION_YAW_180 = 4, 13 | ROTATION_YAW_225 = 5, 14 | ROTATION_YAW_270 = 6, 15 | ROTATION_YAW_315 = 7, 16 | ROTATION_ROLL_180 = 8, 17 | ROTATION_ROLL_180_YAW_45 = 9, 18 | ROTATION_ROLL_180_YAW_90 = 10, 19 | ROTATION_ROLL_180_YAW_135 = 11, 20 | ROTATION_PITCH_180 = 12, 21 | ROTATION_ROLL_180_YAW_225 = 13, 22 | ROTATION_ROLL_180_YAW_270 = 14, 23 | ROTATION_ROLL_180_YAW_315 = 15, 24 | ROTATION_ROLL_90 = 16, 25 | ROTATION_ROLL_90_YAW_45 = 17, 26 | ROTATION_ROLL_90_YAW_90 = 18, 27 | ROTATION_ROLL_90_YAW_135 = 19, 28 | ROTATION_ROLL_270 = 20, 29 | ROTATION_ROLL_270_YAW_45 = 21, 30 | ROTATION_ROLL_270_YAW_90 = 22, 31 | ROTATION_ROLL_270_YAW_135 = 23, 32 | ROTATION_PITCH_90 = 24, 33 | ROTATION_PITCH_270 = 25, 34 | ROTATION_ROLL_270_YAW_270 = 26, 35 | ROTATION_ROLL_180_PITCH_270 = 27, 36 | ROTATION_PITCH_90_YAW_180 = 28, 37 | ROTATION_PITCH_90_ROLL_90 = 29, 38 | ROTATION_YAW_293_PITCH_68_ROLL_90 = 30, 39 | ROTATION_PITCH_90_ROLL_270 = 31, 40 | ROTATION_MAX 41 | }; 42 | 43 | void RotateVector3f(enum Rotation rot, Vector3f_t* v); 44 | 45 | #endif 46 | 47 | -------------------------------------------------------------------------------- /Code Project/SRC/MATH/vector3.h: -------------------------------------------------------------------------------- 1 | #ifndef __VECTOR3_H__ 2 | #define __VECTOR3_H__ 3 | 4 | #include "mathTool.h" 5 | 6 | typedef struct { 7 | float x; 8 | float y; 9 | float z; 10 | } Vector3f_t; 11 | 12 | typedef struct { 13 | double x; 14 | double y; 15 | double z; 16 | } Vector3d_t; 17 | 18 | typedef struct { 19 | int16_t x; 20 | int16_t y; 21 | int16_t z; 22 | } Vector3i_t; 23 | 24 | typedef struct { 25 | int32_t x; 26 | int32_t y; 27 | int32_t z; 28 | } Vector3l_t; 29 | 30 | void Vector3f_Normalize(Vector3f_t* vector); 31 | 32 | Vector3f_t Vector3iTo3f(Vector3i_t vector); 33 | Vector3i_t Vector3fTo3i(Vector3f_t vector); 34 | Vector3f_t Vector3f_Add(Vector3f_t v1, Vector3f_t v2); 35 | Vector3f_t Vector3f_Sub(Vector3f_t v1, Vector3f_t v2); 36 | 37 | Vector3f_t VectorCrossProduct(Vector3f_t a, Vector3f_t b); 38 | Vector3f_t Matrix3MulVector3(float* m, Vector3f_t vector); 39 | Vector3f_t VectorRotateToBodyFrame(Vector3f_t vector, Vector3f_t deltaAngle); 40 | Vector3f_t VectorRotateToEarthFrame(Vector3f_t vector, Vector3f_t deltaAngle); 41 | 42 | void EulerAngleToDCM(Vector3f_t angle, float* dcM); 43 | 44 | void AccVectorToRollPitchAngle(Vector3f_t* angle, Vector3f_t vector); 45 | void MagVectorToYawAngle(Vector3f_t* angle, Vector3f_t vector); 46 | 47 | #endif 48 | 49 | 50 | -------------------------------------------------------------------------------- /Code Project/SRC/MESSAGE/bsklinkDecode.h: -------------------------------------------------------------------------------- 1 | #ifndef _BSKLINKDECODE_H_ 2 | #define _BSKLINKDECODE_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | void BsklinkDecode(uint8_t data); 7 | 8 | #endif 9 | -------------------------------------------------------------------------------- /Code Project/SRC/MESSAGE/bsklinkSend.h: -------------------------------------------------------------------------------- 1 | #ifndef _BSKLINKSEND_H_ 2 | #define _BSKLINKSEND_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | void BsklinkSendFlightData(uint8_t* sendFlag); 7 | void BsklinkSendFlightStatus(uint8_t* sendFlag); 8 | void BsklinkSendSensor(uint8_t* sendFlag); 9 | void BsklinkSendSensorCaliData(uint8_t* sendFlag); 10 | void BsklinkSendSensorCaliCmd(uint8_t* sendFlag, uint8_t type, uint8_t step, uint8_t success); 11 | void BsklinkSendGps(uint8_t* sendFlag); 12 | void BsklinkSendRcData(uint8_t* sendFlag); 13 | void BsklinkSendMotor(uint8_t* sendFlag); 14 | void BsklinkSendBattery(uint8_t* sendFlag); 15 | void BsklinkSendPidAtt(uint8_t* sendFlag); 16 | void BsklinkSendPidPos(uint8_t* sendFlag); 17 | void BsklinkSendPidAck(uint8_t* sendFlag); 18 | void BsklinkSetPidAck(uint8_t ack); 19 | void BsklinkSendSysError(uint8_t* sendFlag); 20 | void BsklinkSendSysWarning(uint8_t* sendFlag); 21 | void BsklinkSendAttAnalyse(uint8_t* sendFlag); 22 | void BsklinkSendVelAnalyse(uint8_t* sendFlag); 23 | void BsklinkSendPosAnalyse(uint8_t* sendFlag); 24 | void BsklinkSendUserDefine(uint8_t* sendFlag); 25 | void BsklinkSendFreqSetup(uint8_t* sendFlag); 26 | void BsklinkSendHeartBeat(uint8_t* sendFlag); 27 | 28 | #endif 29 | 30 | 31 | -------------------------------------------------------------------------------- /Code Project/SRC/MESSAGE/mavlinkDecode.h: -------------------------------------------------------------------------------- 1 | #ifndef _MAVLINKDECODE_H_ 2 | #define _MAVLINKDECODE_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | void MavlinkDecode(uint8_t data); 7 | 8 | #endif 9 | 10 | -------------------------------------------------------------------------------- /Code Project/SRC/MESSAGE/mavlinkNotice.h: -------------------------------------------------------------------------------- 1 | #ifndef _MAVLINKNOTICE_H_ 2 | #define _MAVLINKNOTICE_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | enum MAV_NOTICE_TYPE 7 | { 8 | CAL_START_GYRO, 9 | CAL_START_ACC, 10 | CAL_START_MAG, 11 | CAL_START_LEVEL, 12 | CAL_DONE, 13 | CAL_FAILED, 14 | CAL_PROGRESS_0, 15 | CAL_PROGRESS_10, 16 | CAL_PROGRESS_20, 17 | CAL_PROGRESS_30, 18 | CAL_PROGRESS_40, 19 | CAL_PROGRESS_50, 20 | CAL_PROGRESS_60, 21 | CAL_PROGRESS_70, 22 | CAL_PROGRESS_80, 23 | CAL_PROGRESS_90, 24 | CAL_PROGRESS_100, 25 | CAL_UP_DETECTED, 26 | CAL_DOWN_DETECTED, 27 | CAL_LEFT_DETECTED, 28 | CAL_RIGHT_DETECTED, 29 | CAL_FRONT_DETECTED, 30 | CAL_BACK_DETECTED, 31 | CAL_UP_DONE, 32 | CAL_DOWN_DONE, 33 | CAL_LEFT_DONE, 34 | CAL_RIGHT_DONE, 35 | CAL_FRONT_DONE, 36 | CAL_BACK_DONE, 37 | INIT_WELCOME, 38 | INIT_INIT_START, 39 | INIT_INIT_FINISH, 40 | INIT_HEATING, 41 | INIT_HEAT_FINISH, 42 | INIT_HEAT_DISABLE, 43 | SENSOR_CHECK_START, 44 | SENSOR_CHECK_ERROR, 45 | SENSOR_CHECK_FINISH, 46 | SENSOR_GYRO_UNDETECTED, 47 | SENSOR_GYRO_UNCALI, 48 | SENSOR_GYRO_NEED_CALI, 49 | SENSOR_GYRO_OK, 50 | SENSOR_ACC_UNCALI, 51 | SENSOR_ACC_NEED_CALI, 52 | SENSOR_ACC_OK, 53 | SENSOR_MAG_UNDETECTED, 54 | SENSOR_MAG_UNCALI, 55 | SENSOR_MAG_NEED_CALI, 56 | SENSOR_MAG_OK, 57 | SENSOR_BARO_UNDETECTED, 58 | SENSOR_BARO_OK, 59 | SENSOR_GPS_UNDETECTED, 60 | SENSOR_GPS_OK, 61 | MAV_NOTICE_NUM 62 | }; 63 | 64 | typedef struct { 65 | uint8_t severity; 66 | char* strings; 67 | } MAV_NOTICE_t; 68 | 69 | MAV_NOTICE_t GetMavNoticeValue(uint8_t noticeNum); 70 | 71 | #endif 72 | 73 | -------------------------------------------------------------------------------- /Code Project/SRC/MESSAGE/mavlinkSend.h: -------------------------------------------------------------------------------- 1 | #ifndef _MAVLINKSEND_H_ 2 | #define _MAVLINKSEND_H_ 3 | 4 | #include "mathTool.h" 5 | #include "mavlinkNotice.h" 6 | 7 | void MavlinkSendHeartbeat(uint8_t* sendFlag); 8 | void MavlinkSendSysStatus(uint8_t* sendFlag); 9 | void MavlinkSendParamValue(uint8_t* sendFlag); 10 | void MavlinkSendGpsRawInt(uint8_t* sendFlag); 11 | void MavlinkSendScaledImu(uint8_t* sendFlag); 12 | void MavlinkSendAttitude(uint8_t* sendFlag); 13 | void MavlinkSendLocalPositionNed(uint8_t* sendFlag); 14 | void MavlinkSendRcChannels(uint8_t* sendFlag); 15 | void MavlinkSendCommandAck(uint8_t* sendFlag); 16 | void MavlinkSendMissionRequest(uint8_t* sendFlag); 17 | void MavlinkSendMissionAck(uint8_t* sendFlag); 18 | void MavlinkSendMissionCount(uint8_t* sendFlag); 19 | void MavlinkSendMissionItem(uint8_t* sendFlag); 20 | void MavlinkSendHomePosition(uint8_t* sendFlag); 21 | void MavlinkSendVfrHud(uint8_t* sendFlag); 22 | void MavlinkSendStatusText(uint8_t* sendFlag); 23 | 24 | void MavlinkCurrentParamSet(uint16_t num); 25 | void MavlinkSetCommandAck(uint16_t command, uint8_t result); 26 | bool MavStatusTextSendCheck(void); 27 | void MavlinkSendNoticeEnable(uint16_t noticeNum); 28 | void MavlinkSendNotice(uint16_t noticeNum); 29 | void MavlinkSendNoticeProgress(uint8_t progress); 30 | 31 | #endif 32 | 33 | 34 | 35 | 36 | -------------------------------------------------------------------------------- /Code Project/SRC/MESSAGE/message.h: -------------------------------------------------------------------------------- 1 | #ifndef _MESSAGE_H_ 2 | #define _MESSAGE_H_ 3 | 4 | #include "mathTool.h" 5 | #include "bsklink.h" 6 | #include "mavlink.h" 7 | 8 | #define MAX_SEND_FREQ 100 //最大发送频率 单位:Hz 9 | 10 | #define MAVLINK_SYSTEM_ID 1 11 | #define MAVLINK_COMPONENT_ID MAV_COMP_ID_AUTOPILOT1 12 | 13 | typedef union 14 | { 15 | int8_t i8; 16 | int16_t i16; 17 | int32_t i32; 18 | float f32; 19 | uint8_t byte[4]; 20 | } DATA_TYPE_t; 21 | 22 | void MessageInit(void); 23 | void MessageSendLoop(void); 24 | void MessageSensorCaliFeedbackEnable(uint8_t type, uint8_t step, uint8_t success); 25 | void BsklinkSetMsgFreq(BSKLINK_MSG_ID_FREQ_SETUP_t payload); 26 | void BsklinkSendEnable(uint8_t msgid); 27 | void MavlinkSendEnable(uint8_t msgid); 28 | void DataSend(uint8_t *data, uint8_t length); 29 | bool GetMessageStatus(void); 30 | 31 | #endif 32 | 33 | 34 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/LC302.c: -------------------------------------------------------------------------------- 1 | // 2 | // Created by liuyufanlyf on 2021/06/15. 3 | // 4 | 5 | #include "LC302.h" 6 | #include "stdint.h" 7 | #include "string.h" 8 | #include "stdbool.h" 9 | #include "drv_uart.h" 10 | 11 | typedef struct { 12 | uint8_t frame_head; 13 | uint8_t frame_length; 14 | int16_t flow_x_integral; 15 | int16_t flow_y_integral; 16 | uint16_t integration_timespan; 17 | uint16_t ground_distance; 18 | uint8_t valid; 19 | uint8_t version; 20 | uint8_t check; 21 | uint8_t frame_tail; 22 | 23 | uint8_t raw[14]; 24 | bool available 25 | } lc302_t; 26 | 27 | lc302_t lc302; 28 | 29 | void LC302_init(void) { 30 | 31 | } 32 | 33 | void LC302_Decode(uint8_t data) { 34 | static uint32_t lastTime; 35 | static uint32_t dataCnt = 0; 36 | 37 | if (GetSysTimeMs() < 2000) 38 | return; 39 | 40 | uint32_t deltaT = GetSysTimeMs() - lastTime; 41 | lastTime = GetSysTimeMs(); 42 | 43 | //数据间隔大于3ms则可以认为新的一帧开始了 44 | if (deltaT > 3) { 45 | dataCnt = 0; 46 | } 47 | 48 | lc302.raw[dataCnt++] = data; 49 | 50 | if (dataCnt == 14) { 51 | if (lc302.raw[0] == 0xFE && lc302.raw[13] == 0x55) { 52 | lc302.frame_length = lc302.raw[1]; 53 | lc302.flow_x_integral = lc302.raw[2] + (lc302.raw[3] << 8); 54 | lc302.flow_y_integral = lc302.raw[4] + (lc302.raw[5] << 8); 55 | lc302.integration_timespan = lc302.raw[6] + (lc302.raw[7] << 8); 56 | lc302.ground_distance = lc302.raw[8] + (lc302.raw[9] << 8); 57 | lc302.valid = lc302.raw[10]; 58 | lc302.version = lc302.raw[11]; 59 | lc302.check = lc302.raw[12]; 60 | 61 | //如果valid值为0xF5,则说明此帧有效 62 | if (lc302.valid != 0xF5) { 63 | lc302.flow_x_integral = 0; 64 | lc302.flow_y_integral = 0; 65 | lc302.available = false; 66 | } else { 67 | lc302.available = true; 68 | } 69 | } else { 70 | lc302.available = false; 71 | } 72 | } 73 | } 74 | 75 | int LC302_get_X_Integral(void) { 76 | return lc302.flow_x_integral; 77 | } 78 | 79 | int LC302_get_Y_Integral(void) { 80 | return lc302.flow_y_integral; 81 | } 82 | 83 | int LC302_getTimeSpan(void){ 84 | return lc302.integration_timespan; 85 | } 86 | 87 | bool LC302_getAvaliable(void) { 88 | return lc302.available; 89 | } 90 | 91 | 92 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/LC302.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Liuyufanlyf on 2021/06/15. 3 | // 4 | 5 | #ifndef LC302_H 6 | #define LC302_H 7 | 8 | #include "board.h" 9 | 10 | void LC302_init(void); 11 | 12 | void LC302_Decode(uint8_t data); 13 | 14 | int LC302_get_X_Integral(void); 15 | 16 | int LC302_get_Y_Integral(void); 17 | 18 | int LC302_getTimeSpan(void); 19 | 20 | bool LC302_getAvaliable(void); 21 | 22 | #endif //LC302_H 23 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/Servo.c: -------------------------------------------------------------------------------- 1 | #include "Servo.h" 2 | 3 | //设置舵机的目标角度,范围-90°-90° 4 | void ServoSetDeg(uint8_t num, int8_t value) { 5 | ServoControlPWMSet(num, value); 6 | } -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/Servo.h: -------------------------------------------------------------------------------- 1 | #ifndef _SERVO_H 2 | #define _SERVO_H 3 | 4 | #include "board.h" 5 | #include "drv_pwm.h" 6 | 7 | void ServoSetDeg(uint8_t num, int8_t value); 8 | 9 | #endif 10 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/battery.c: -------------------------------------------------------------------------------- 1 | /********************************************************************************************************** 2 | 天穹飞控 —— 致力于打造中国最好的多旋翼开源飞控 3 | Github: github.com/loveuav/BlueSkyFlightControl 4 | 技术讨论:bbs.loveuav.com/forum-68-1.html 5 | * @文件 battery.c 6 | * @说明 电池电压电流检测 7 | * @版本 V1.0 8 | * @作者 BlueSky 9 | * @网站 bbs.loveuav.com 10 | * @日期 2018.06 11 | **********************************************************************************************************/ 12 | #include "battery.h" 13 | #include "drv_adc.h" 14 | 15 | // 一般建议锂电池在 3.7V 充电 16 | #define VOLTAGE_LOW 370 * 3 17 | #define VOLTAGE_CRITICAL_LOW 350 * 3 18 | 19 | static float batVoltage; 20 | static float batCurrent; 21 | 22 | /********************************************************************************************************** 23 | *函 数 名: BatteryVoltageUpdate 24 | *功能说明: 电池电压采样更新 25 | *形 参: 无 26 | *返 回 值: 无 27 | **********************************************************************************************************/ 28 | void BatteryVoltageUpdate(void) 29 | 30 | { 31 | if(batVoltage == 0) 32 | { 33 | batVoltage = GetVoltageAdcValue() * ADC_VOLTAGE_COEF; 34 | } 35 | else 36 | { 37 | batVoltage = batVoltage * 0.999f + GetVoltageAdcValue() * ADC_VOLTAGE_COEF * 0.001f; 38 | } 39 | } 40 | 41 | /********************************************************************************************************** 42 | *函 数 名: BatteryCurrentUpdate 43 | *功能说明: 电池电流采样更新 44 | *形 参: 无 45 | *返 回 值: 无 46 | **********************************************************************************************************/ 47 | void BatteryCurrentUpdate(void) 48 | { 49 | if(batCurrent == 0) 50 | { 51 | batCurrent = GetCurrentAdcValue() * ADC_CURRENT_COEF; 52 | } 53 | else 54 | { 55 | batCurrent = batCurrent * 0.99f + GetCurrentAdcValue() * ADC_CURRENT_COEF * 0.01f; 56 | } 57 | } 58 | 59 | /********************************************************************************************************** 60 | *函 数 名: GetBatteryVoltage 61 | *功能说明: 获取电池电压 62 | *形 参: 无 63 | *返 回 值: 电压值 64 | **********************************************************************************************************/ 65 | int16_t GetBatteryVoltage(void) 66 | { 67 | return batVoltage; 68 | } 69 | 70 | /********************************************************************************************************** 71 | *函 数 名: GetBatteryCurrent 72 | *功能说明: 获取电池电流 73 | *形 参: 无 74 | *返 回 值: 电压值 75 | **********************************************************************************************************/ 76 | int16_t GetBatteryCurrent(void) 77 | { 78 | return batCurrent; 79 | } 80 | 81 | /********************************************************************************************************** 82 | *函 数 名: GetBatteryStatus 83 | *功能说明: 获取电池状态 84 | *形 参: 无 85 | *返 回 值: 状态 86 | **********************************************************************************************************/ 87 | uint8_t GetBatteryStatus(void) 88 | { 89 | if(batVoltage < VOLTAGE_CRITICAL_LOW) 90 | { 91 | return BATTERY_CRITICAL_LOW; 92 | } 93 | else if(batVoltage < VOLTAGE_LOW) 94 | { 95 | return BATTERY_LOW; 96 | } 97 | else 98 | { 99 | return BATTERY_NORMAL; 100 | } 101 | } 102 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/battery.h: -------------------------------------------------------------------------------- 1 | #ifndef __BATTERY_H 2 | #define __BATTERY_H 3 | 4 | #include "mathTool.h" 5 | 6 | enum 7 | { 8 | BATTERY_NORMAL, 9 | BATTERY_LOW, 10 | BATTERY_CRITICAL_LOW 11 | }; 12 | 13 | void BatteryVoltageUpdate(void); 14 | void BatteryCurrentUpdate(void); 15 | 16 | int16_t GetBatteryVoltage(void); 17 | int16_t GetBatteryCurrent(void); 18 | uint8_t GetBatteryStatus(void); 19 | 20 | #endif 21 | 22 | 23 | 24 | 25 | 26 | 27 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/buzzer.c: -------------------------------------------------------------------------------- 1 | #include "buzzer.h" 2 | 3 | void buzzerRing() { 4 | BuzzerPWMSet(1000); 5 | } 6 | 7 | void buzzerStop() { 8 | BuzzerPWMSet(0); 9 | } 10 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/buzzer.h: -------------------------------------------------------------------------------- 1 | #ifndef _BUZZER_H 2 | #define _BUZZER_H 3 | 4 | #include "board.h" 5 | #include "drv_pwm.h" 6 | 7 | void buzzerRing(); 8 | 9 | void buzzerStop(); 10 | 11 | #endif 12 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/icm20602.h: -------------------------------------------------------------------------------- 1 | #ifndef __ICM20602_H 2 | #define __ICM20602_H 3 | 4 | #include "mathTool.h" 5 | 6 | bool ICM20602_Detect(void); 7 | void ICM20602_Init(void); 8 | 9 | void ICM20602_ReadAcc(Vector3f_t* acc); 10 | void ICM20602_ReadGyro(Vector3f_t* gyro); 11 | void ICM20602_ReadTemp(float* temp); 12 | 13 | #endif 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/icm20689.h: -------------------------------------------------------------------------------- 1 | #ifndef __ICM20689_H 2 | #define __ICM20689_H 3 | 4 | #include "mathTool.h" 5 | 6 | bool ICM20689_Detect(void); 7 | void ICM20689_Init(void); 8 | 9 | void ICM20689_ReadAcc(Vector3f_t* acc); 10 | void ICM20689_ReadGyro(Vector3f_t* gyro); 11 | void ICM20689_ReadTemp(float* temp); 12 | 13 | #endif 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/icm20948.h: -------------------------------------------------------------------------------- 1 | #include "vector3.h" 2 | #include "stdbool.h" 3 | 4 | #define USER_BANK_SEL (0x7F) 5 | #define USER_BANK_0 (0x00) 6 | #define USER_BANK_1 (0x10) 7 | #define USER_BANK_2 (0x20) 8 | #define USER_BANK_3 (0x30) 9 | 10 | #define PWR_MGMT_1 (0x06) 11 | #define PWR_MGMT_2 (0x07) 12 | #define GYRO_CONFIG_1 (0x01) 13 | 14 | #define CLK_BEST_AVAIL (0x01) 15 | #define GYRO_RATE_250 (0x00) 16 | #define GYRO_LPF_17HZ (0x29) 17 | 18 | void ICM20489_PowerOn(); 19 | bool ICM20948_Detect(void); 20 | uint16_t ICM20948_Init(void); 21 | 22 | void ICM20948_ReadAcc(Vector3f_t* acc); 23 | void ICM20948_ReadGyro(Vector3f_t* gyro); 24 | void ICM20948_ReadMag(int16_t magn[3]); 25 | void ICM20948_ReadTemp(float* temp); 26 | 27 | void ICM20948_SelectBank(uint8_t bank); 28 | void ICM20948_Disable_I2C(void); 29 | void ICM20948_CSHigh(void); 30 | void ICM20948_CSLow(void); 31 | void ICM20948_SetClock(uint8_t clk); 32 | void ICM20948_AccelGyroOff(void); 33 | void ICM20948_AccelGyroOn(void); 34 | void ICM20948_SetGyroRateLPF(uint8_t rate, uint8_t lpf); 35 | void ICM20948_SetGyroLPF(uint8_t lpf); 36 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/ist8310.h: -------------------------------------------------------------------------------- 1 | #ifndef __IST8310_H 2 | #define __IST8310_H 3 | 4 | #include "mathTool.h" 5 | 6 | bool IST8310_Detect(void); 7 | void IST8310_Init(void); 8 | void IST8310_Update(void); 9 | void IST8310_Read(Vector3f_t* mag); 10 | 11 | 12 | #endif 13 | 14 | 15 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/module.h: -------------------------------------------------------------------------------- 1 | #ifndef __MODULE_H__ 2 | #define __MODULE_H__ 3 | 4 | #include "mathTool.h" 5 | 6 | void GyroSensorInit(void); 7 | void MagSensorInit(void); 8 | void BaroSensorInit(void); 9 | void GPSModuleInit(void); 10 | void ToFAltitmeterInit(void); 11 | void OptFlowInit(void); 12 | 13 | void GyroSensorRead(Vector3f_t* gyro); 14 | void AccSensorRead(Vector3f_t* acc); 15 | void TempSensorRead(float* temp); 16 | 17 | void MagSensorUpdate(void); 18 | void MagSensorRead(Vector3f_t* mag); 19 | void BaroSensorRead(int32_t* baroAlt); 20 | void BaroSensorUpdate(void); 21 | void BaroTemperatureRead(float* temp); 22 | 23 | void TempControlSet(int16_t value); 24 | 25 | #endif 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/mpu6500.h: -------------------------------------------------------------------------------- 1 | #ifndef __MPU6500_H 2 | #define __MPU6500_H 3 | 4 | #include "mathTool.h" 5 | 6 | bool MPU6500_Detect(void); 7 | void MPU6500_Init(void); 8 | 9 | void MPU6500_ReadAcc(Vector3f_t* acc); 10 | void MPU6500_ReadGyro(Vector3f_t* gyro); 11 | void MPU6500_ReadTemp(float* temp); 12 | 13 | #endif 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/ms5611.h: -------------------------------------------------------------------------------- 1 | #ifndef __MS5611_H 2 | #define __MS5611_H 3 | 4 | #include "mathTool.h" 5 | 6 | bool MS5611_Detect(void); 7 | void MS5611_Init(void); 8 | 9 | void MS5611_Update(void); 10 | void MS5611_Read(int32_t* baroAlt); 11 | void MS5611_ReadTemp(float* temp); 12 | 13 | #endif 14 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/rgb.h: -------------------------------------------------------------------------------- 1 | #ifndef __RGB_H 2 | #define __RGB_H 3 | 4 | #include "mathTool.h" 5 | 6 | void RGB_Init(void); 7 | void RGB_Flash(void); 8 | 9 | #endif 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/spl06-001.h: -------------------------------------------------------------------------------- 1 | #ifndef SPL06_01_H 2 | #define SPL06_01_H 3 | 4 | #include 5 | #include "main.h" 6 | 7 | //#define HW_ADR 0x77 //SDO HIGH OR NC 8 | #define HW_ADR 0x76 //SDO LOW 9 | #define CONTINUOUS_PRESSURE 1 10 | #define CONTINUOUS_TEMPERATURE 2 11 | #define CONTINUOUS_P_AND_T 3 12 | #define PRESSURE_SENSOR 0 13 | #define TEMPERATURE_SENSOR 1 14 | 15 | 16 | struct spl0601_calib_param_t { 17 | int16_t c0; 18 | int16_t c1; 19 | int32_t c00; 20 | int32_t c10; 21 | int16_t c01; 22 | int16_t c11; 23 | int16_t c20; 24 | int16_t c21; 25 | int16_t c30; 26 | }; 27 | 28 | struct spl0601_t { 29 | struct spl0601_calib_param_t calib_param;/** 3) { 28 | dataCnt = 0; 29 | } 30 | 31 | raw[dataCnt++] = data; 32 | 33 | if (dataCnt == 9) { 34 | 35 | if (raw[0] == 0x59 && raw[1] == 0x59) { 36 | // Calculate the checksum 37 | uint16_t checksum = 0; 38 | for (uint8_t i = 0; i < 8; i++) { 39 | checksum += raw[i]; 40 | } 41 | checksum &= 0xFF; 42 | 43 | if (checksum == raw[8]) { 44 | tf_data.length = raw[2] + (raw[3] << 8); 45 | tf_data.singal_strength = raw[4] + (raw[5] << 8); 46 | if (tf_data.singal_strength > 100 && tf_data.singal_strength < 65535) { 47 | tf_data.avaliable = true; 48 | memset(raw, 0, 16); 49 | } else { 50 | tf_data.avaliable = false; 51 | memset(raw, 0, 16); 52 | return; 53 | } 54 | } else { 55 | tf_data.avaliable = false; 56 | memset(raw, 0, 16); 57 | return; 58 | } 59 | } else { 60 | tf_data.avaliable = false; 61 | memset(raw, 0, 16); 62 | return; 63 | } 64 | } 65 | } 66 | 67 | int TFminiPlus_GetDistance(void) { 68 | return tf_data.length; 69 | } 70 | 71 | int TFminiPlus_GetSignalStrength(void) { 72 | return tf_data.singal_strength; 73 | } 74 | 75 | bool TFminiPlus_GetAvaliable(void) { 76 | bool temp = tf_data.avaliable; 77 | tf_data.avaliable = false; 78 | return temp; 79 | } -------------------------------------------------------------------------------- /Code Project/SRC/MODULE/tfminiplus.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Liuyufanlyf on 2021/06/05. 3 | // 4 | 5 | #ifndef TFMINIPLUS_H 6 | #define TFMINIPLUS_H 7 | 8 | #include "stdbool.h" 9 | 10 | #include "usart.h" 11 | 12 | typedef struct { 13 | int length; 14 | int singal_strength; 15 | uint8_t raw_data[9]; 16 | bool avaliable; 17 | } tfminiplus_data_t; 18 | 19 | extern tfminiplus_data_t tf_data; 20 | 21 | void TFminiPlus_Init(void); 22 | 23 | void TFminiPlus_Decode(uint8_t data); 24 | 25 | int TFminiPlus_GetDistance(void); 26 | 27 | int TFminiPlus_GetSignalStrength(void); 28 | 29 | bool TFminiPlus_GetAvaliable(void); 30 | 31 | #endif //TFMINIPLUS_H 32 | -------------------------------------------------------------------------------- /Code Project/SRC/NAVIGATION/ahrs.h: -------------------------------------------------------------------------------- 1 | #ifndef _AHRS_H_ 2 | #define _AHRS_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | typedef struct { 7 | Vector3f_t angle; 8 | Vector3f_t angleError; 9 | Vector3f_t angleMeasure; 10 | 11 | Vector3f_t accEf; 12 | Vector3f_t accEfLpf; 13 | Vector3f_t accBfOffset; 14 | 15 | Vector3f_t gyroEf; 16 | 17 | Vector3f_t centripetalAcc; 18 | Vector3f_t centripetalAccBf; 19 | } AHRS_t; 20 | 21 | void AHRSInit(void); 22 | void AttitudeEstimate(Vector3f_t gyro, Vector3f_t acc, Vector3f_t mag); 23 | void BodyFrameToEarthFrame(Vector3f_t angle, Vector3f_t vector, Vector3f_t* vectorEf); 24 | void EarthFrameToBodyFrame(Vector3f_t angle, Vector3f_t vector, Vector3f_t* vectorBf); 25 | 26 | void AttCovarianceSelfAdaptation(void); 27 | 28 | Vector3f_t GetCopterAngle(void); 29 | Vector3f_t GetCopterAccEf(void); 30 | Vector3f_t GetCopterAccEfLpf(void); 31 | Vector3f_t GetCentripetalAcc(void); 32 | Vector3f_t GetCentripetalAccBf(void); 33 | Vector3f_t GetAngleMeasure(void); 34 | Vector3f_t GetAngleEstError(void); 35 | 36 | uint8_t RollOverDetect(void); 37 | 38 | #endif 39 | 40 | 41 | 42 | 43 | 44 | 45 | -------------------------------------------------------------------------------- /Code Project/SRC/NAVIGATION/ahrsAux.h: -------------------------------------------------------------------------------- 1 | #ifndef _AHRSAUX_H_ 2 | #define _AHRSAUX_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | typedef struct { 7 | Vector3f_t angle; 8 | float q[4]; 9 | Vector3f_t angleError; 10 | 11 | Vector3f_t vectorRollPitch; 12 | 13 | Vector3f_t accEf; 14 | } AHRSAUX_t; 15 | 16 | void AHRSAuxInit(void); 17 | void AttitudeAuxEstimate(Vector3f_t gyro, Vector3f_t acc, Vector3f_t mag); 18 | 19 | void RollPitchUpdateByKF(Vector3f_t* angle, Vector3f_t gyro, Vector3f_t acc, float deltaT); 20 | void QuaternionUpdateByCF(float q[4], Vector3f_t* angle, Vector3f_t gyro, Vector3f_t acc, Vector3f_t mag, float deltaT); 21 | 22 | Vector3f_t GetSportAccEf(void); 23 | Vector3f_t GetAuxAngle(void); 24 | 25 | #endif 26 | 27 | 28 | -------------------------------------------------------------------------------- /Code Project/SRC/NAVIGATION/navigation.h: -------------------------------------------------------------------------------- 1 | #ifndef _NAVIGATION_H_ 2 | #define _NAVIGATION_H_ 3 | 4 | #include "mathTool.h" 5 | 6 | enum 7 | { 8 | GPS_VEL_X = 0, 9 | GPS_VEL_Y, 10 | GPS_VEL_Z, 11 | BARO_VEL, 12 | TOF_VEL 13 | }; 14 | 15 | typedef struct { 16 | Vector3f_t accel; 17 | Vector3f_t accel_bias; 18 | 19 | Vector3f_t velocity; 20 | float velMeasure[6]; 21 | 22 | Vector3f_t position; 23 | Vector3f_t posMeasure; 24 | } NAVGATION_t; 25 | 26 | void NavigationInit(void); 27 | void VelocityEstimate(void); 28 | void PositionEstimate(void); 29 | 30 | void AltCovarianceSelfAdaptation(void); 31 | void PosCovarianceSelfAdaptation(void); 32 | 33 | Vector3f_t GetCopterAccel(void); 34 | Vector3f_t GetAccelBias(void); 35 | Vector3f_t GetCopterVelocity(void); 36 | float* GetCopterVelMeasure(void); 37 | Vector3f_t GetCopterPosition(void); 38 | Vector3f_t GetCopterPosMeasure(void); 39 | 40 | void NavigationReset(void); 41 | 42 | #endif 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | -------------------------------------------------------------------------------- /Code Project/SRC/SENSOR/ToFaltimeter.c: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Liuyufanlyf on 2021/06/14. 3 | // 4 | 5 | #include "ToFaltimeter.h" 6 | 7 | #include "board.h" 8 | #include "flightStatus.h" 9 | #include "faultDetect.h" 10 | #include "tfminiplus.h" 11 | #include "ahrs.h" 12 | 13 | typedef struct { 14 | int32_t alt; 15 | int32_t lastAlt; 16 | float velocity; 17 | int32_t alt_offset; 18 | } TOFALTIMETER_t; 19 | 20 | TOFALTIMETER_t tofaltimeter; 21 | 22 | static void ToFAltimeterDetectCheck(int32_t ToFAlt); 23 | 24 | void ToFAltimeterDataTreat(void) { 25 | static uint64_t lastTime = 0; 26 | int32_t ToFAltTemp; 27 | 28 | float deltaT = (GetSysTimeUs() - lastTime) * 1e-6; 29 | lastTime = GetSysTimeUs(); 30 | 31 | ToFAltTemp = TFminiPlus_GetDistance(); 32 | 33 | // 是否需要角度补偿? 34 | // 若姿态角限制在 10° 以内,误差不超过 2% 35 | ToFAltTemp = ToFAltTemp * cosf(Radians(GetAngleMeasure().x)) * cosf(Radians(GetAngleMeasure().y)); 36 | 37 | // 高度低通滤波 38 | // 激光测距是否准到能直接使用作为高度? 39 | tofaltimeter.alt = ToFAltTemp; 40 | 41 | // 速度低通滤波 42 | tofaltimeter.velocity = 43 | tofaltimeter.velocity * 0.65f + ((tofaltimeter.alt - tofaltimeter.lastAlt) / deltaT) * 0.35f; 44 | tofaltimeter.lastAlt = tofaltimeter.alt; 45 | 46 | ToFAltimeterDetectCheck(tofaltimeter.lastAlt); 47 | } 48 | 49 | int32_t ToFAltimeterGetAlt(void) { 50 | return tofaltimeter.alt; 51 | } 52 | 53 | float ToFAltimeterGetVelocity(void) { 54 | return tofaltimeter.velocity; 55 | } 56 | 57 | static void ToFAltimeterDetectCheck(int32_t ToFAlt) { 58 | static uint32_t cnt; 59 | static int32_t lastToFAlt = 0; 60 | 61 | if (ToFAlt == lastToFAlt) { 62 | cnt++; 63 | if (cnt > 100) { 64 | //未检测到ToF传感器 65 | FaultDetectSetError(TOF_UNDETECTED); 66 | } 67 | } else { 68 | cnt = 0; 69 | FaultDetectResetError(TOF_UNDETECTED); 70 | } 71 | 72 | lastToFAlt = ToFAlt; 73 | } 74 | 75 | -------------------------------------------------------------------------------- /Code Project/SRC/SENSOR/ToFaltimeter.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Liuyufanlyf on 2021/06/14. 3 | // 4 | 5 | #ifndef TOF_ALTIMETER_H 6 | #define TOF_ALTIMETER_H 7 | 8 | #include "stdint.h" 9 | #include "stdbool.h" 10 | 11 | void ToFAltimeterDataTreat(void); 12 | 13 | int32_t ToFAltimeterGetAlt(void); 14 | 15 | float ToFAltimeterGetVelocity(void); 16 | 17 | 18 | #endif //TOF_ALTIMETER_H 19 | -------------------------------------------------------------------------------- /Code Project/SRC/SENSOR/accelerometer.h: -------------------------------------------------------------------------------- 1 | #ifndef __ACCELEROMETER_H 2 | #define __ACCELEROMETER_H 3 | 4 | #include "sensor.h" 5 | 6 | typedef struct { 7 | Vector3f_t data; 8 | Vector3f_t dataLpf; 9 | float mag; 10 | float vibraCoef; 11 | LPF2ndData_t lpf_2nd; 12 | SENSOR_CALI_t cali; 13 | SENSOR_CALI_t levelCali; 14 | } ACCELEROMETER_t; 15 | 16 | void AccPreTreatInit(void); 17 | void AccDataPreTreat(Vector3f_t accRaw, Vector3f_t* accData); 18 | void AccCalibration(Vector3f_t accRaw); 19 | void AccScaleCalibrate(Vector3f_t* acc); 20 | void ImuLevelCalibration(void); 21 | 22 | Vector3f_t GetAccOffsetCaliData(void); 23 | Vector3f_t GetAccScaleCaliData(void); 24 | Vector3f_t GetLevelCalibraData(void); 25 | 26 | void AccCalibrateEnable(void); 27 | void LevelCalibrateEnable(void); 28 | 29 | float GetAccMag(void); 30 | Vector3f_t AccGetData(void); 31 | Vector3f_t AccLpfGetData(void); 32 | 33 | #endif 34 | 35 | 36 | 37 | -------------------------------------------------------------------------------- /Code Project/SRC/SENSOR/barometer.h: -------------------------------------------------------------------------------- 1 | #ifndef __BAROMETER_H 2 | #define __BAROMETER_H 3 | 4 | #include "sensor.h" 5 | 6 | void BaroDataPreTreat(void); 7 | int32_t BaroGetAlt(void); 8 | float BaroGetTemp(void); 9 | float BaroGetVelocity(void); 10 | 11 | #endif 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /Code Project/SRC/SENSOR/gps.h: -------------------------------------------------------------------------------- 1 | #ifndef __GPS_H 2 | #define __GPS_H 3 | 4 | #include "sensor.h" 5 | 6 | void GpsDataPreTreat(void); 7 | void TransVelToBodyFrame(Vector3f_t velEf, Vector3f_t* velBf, float yaw); 8 | void TransVelToEarthFrame(Vector3f_t velBf, Vector3f_t* velEf, float yaw); 9 | float GetMagDeclination(void); 10 | bool GpsGetFixStatus(void); 11 | float GpsGetAccuracy(void); 12 | Vector3f_t GpsGetVelocity(void); 13 | Vector3f_t GpsGetPosition(void); 14 | 15 | void GpsResetHomePosition(void); 16 | void GpsTransToLocalPosition(Vector3f_t* position, double lat, double lon); 17 | 18 | float GetDirectionToHome(Vector3f_t position); 19 | float GetDistanceToHome(Vector3f_t position); 20 | float GetDirectionOfTwoPoint(Vector3f_t point1, Vector3f_t point2); 21 | Vector3f_t GetHomePosition(void); 22 | void GetHomeLatitudeAndLongitude(double* lat, double* lon); 23 | 24 | #endif 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | -------------------------------------------------------------------------------- /Code Project/SRC/SENSOR/gyroscope.h: -------------------------------------------------------------------------------- 1 | #ifndef __GYROSCOPE_H 2 | #define __GYROSCOPE_H 3 | 4 | #include "sensor.h" 5 | 6 | typedef struct { 7 | Vector3f_t data; 8 | Vector3f_t dataLpf; 9 | float temperature; 10 | LPF2ndData_t lpf_2nd; 11 | SENSOR_CALI_t cali; 12 | } GYROSCOPE_t; 13 | 14 | void GyroPreTreatInit(void); 15 | void GyroDataPreTreat(Vector3f_t gyroRaw, float temperature, Vector3f_t* gyroData, Vector3f_t* gyroLpfData); 16 | void GyroCalibration(Vector3f_t gyroRaw); 17 | 18 | uint8_t GetGyroCaliStatus(void); 19 | void GyroCalibrateEnable(void); 20 | 21 | Vector3f_t GyroGetData(void); 22 | Vector3f_t GyroLpfGetData(void); 23 | float GyroGetTemp(void); 24 | Vector3f_t GetGyroOffsetCaliData(void); 25 | 26 | #endif 27 | 28 | 29 | 30 | -------------------------------------------------------------------------------- /Code Project/SRC/SENSOR/magnetometer.h: -------------------------------------------------------------------------------- 1 | #ifndef __MAGNETOMETER_H 2 | #define __MAGNETOMETER_H 3 | 4 | #include "sensor.h" 5 | 6 | typedef struct { 7 | Vector3f_t data; 8 | float mag; 9 | SENSOR_CALI_t cali; 10 | float earthMag; 11 | 12 | } MAGNETOMETER_t; 13 | 14 | void MagCaliDataInit(void); 15 | void MagDataPreTreat(void); 16 | void MagCalibration(void); 17 | Vector3f_t MagGetData(void); 18 | void MagCalibrateEnable(void); 19 | 20 | Vector3f_t GetMagOffsetCaliData(void); 21 | Vector3f_t GetMagScaleCaliData(void); 22 | 23 | #endif 24 | 25 | 26 | 27 | -------------------------------------------------------------------------------- /Code Project/SRC/SENSOR/optflow.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Liuyufanlyf on 2021/06/14. 3 | // 4 | 5 | #ifndef OPTFLOW_H 6 | #define OPTFLOW_H 7 | 8 | #include "stdint.h" 9 | #include "stdbool.h" 10 | #include "mathTool.h" 11 | 12 | void OptFlowDataTreat(void); 13 | 14 | void OptFlowDataClear(void); 15 | 16 | float OptFlowGetGroundPositionX(void); 17 | 18 | float OptFlowGetGroundPositionY(void); 19 | 20 | float OptFlowGetGroundVelocityX(void); 21 | 22 | float OptFlowGetGroundVelocityY(void); 23 | 24 | float OptFlowGetLPFVelocityX(void); 25 | 26 | float OptFlowGetLPFVelocityY(void); 27 | 28 | float OptFlowGetGyroPhaseX(void); 29 | 30 | float OptFlowGetGyroPhaseY(void); 31 | 32 | void OptFlowClearGroundPosition(void); 33 | 34 | #endif //OPTFLOW_H 35 | -------------------------------------------------------------------------------- /Code Project/SRC/SENSOR/sensor.h: -------------------------------------------------------------------------------- 1 | #ifndef __SENSOR_H 2 | #define __SENSOR_H 3 | 4 | #include "mathTool.h" 5 | #include "lowPassFilter.h" 6 | 7 | //默认设置传感器自带低通滤波频率为42Hz 8 | 9 | //陀螺仪低通滤波截止频率 10 | //二次低通滤波的陀螺仪数据用于角速度环控制 11 | //频率过低,信号延迟大,会导致控制发散 12 | //频率过高,信号噪声大,会增加高频抖动 13 | //要达到最佳效果,需经调试选取最佳的截止频率 14 | //飞行器越小,系统惯性越小,所需的控制频率越高,对信号实时性的要求也就越高 15 | //450轴距左右的飞机,截止频率不低于50就好,要根据实际情况选取,比如有时过软的硬件减震措施也会增加实际信号延迟 16 | #define GYRO_LPF_CUT 88 17 | 18 | //加速度低通滤波截止频率 19 | //二次低通滤波的加速度数据主要用于计算模值 20 | #define ACC_LPF_CUT 30 21 | 22 | //传感器恒温目标值,单位为摄氏度 23 | #define SENSOR_TEMP_KEPT 50 24 | 25 | //传感器类型 26 | enum 27 | { 28 | GYRO, 29 | ACC, 30 | MAG, 31 | ANGLE, 32 | BARO, 33 | ESC 34 | }; 35 | 36 | //飞控放置方向 37 | enum ORIENTATION_STATUS 38 | { 39 | ORIENTATION_UP, 40 | ORIENTATION_DOWN, 41 | ORIENTATION_LEFT, 42 | ORIENTATION_RIGHT, 43 | ORIENTATION_FRONT, 44 | ORIENTATION_BACK, 45 | }; 46 | 47 | //传感器健康状态 48 | enum SENSOR_HEALTH 49 | { 50 | SENSOR_NORMAL, 51 | SENSOR_UNHEALTH 52 | }; 53 | 54 | typedef struct 55 | { 56 | Vector3f_t offset; //零偏误差 57 | Vector3f_t scale; //比例误差 58 | bool should_cali; //传感器校准标志位 59 | bool success; //校准成功标志位 60 | uint8_t step; //步骤标志位 61 | } SENSOR_CALI_t; 62 | 63 | typedef struct 64 | { 65 | float gyro_offset; 66 | float acc_offset; 67 | float mag_offset; 68 | enum SENSOR_HEALTH gyro; 69 | enum SENSOR_HEALTH acc; 70 | enum SENSOR_HEALTH mag; 71 | } SENSOR_HEALTH_t; 72 | 73 | void ImuTempControlInit(void); 74 | bool SensorCheckStatus(void); 75 | void SensorHealthCheck(void); 76 | void ImuTempControl(float tempMeasure); 77 | void ImuOrientationDetect(void); 78 | 79 | enum ORIENTATION_STATUS GetImuOrientation(void); 80 | enum SENSOR_HEALTH GetGyroHealthStatus(void); 81 | enum SENSOR_HEALTH GetAccHealthStatus(void); 82 | 83 | #endif 84 | 85 | 86 | -------------------------------------------------------------------------------- /Code Project/SRC/SYSTEM/faultDetect.h: -------------------------------------------------------------------------------- 1 | #ifndef __FAULTDETECT_H__ 2 | #define __FAULTDETECT_H__ 3 | 4 | #include "mathTool.h" 5 | 6 | //错误类型 7 | enum ERROR_TYPE 8 | { 9 | ERROR_RESERVE1, 10 | GYRO_UNDETECTED, //未检测到陀螺仪传感器 11 | ACC_UNDETECTED, //未检测到加速度传感器 12 | MAG_UNDETECTED, //未检测到地磁传感器 13 | BARO_UNDETECTED, //未检测到气压传感器 14 | GPS_UNDETECTED, //未检测到GPS 15 | OPTICALFLOW_UNDETECTED, //未检测到光流 16 | ULTRASONIC_UNDETECTED, //未检测到超声波传感器 17 | TOF_UNDETECTED, //未检测到TOF传感器 18 | ERROR_RESERVE2, 19 | ERROR_RESERVE3, 20 | ERROR_RESERVE4, 21 | ERROR_RESERVE5, 22 | GYRO_UNCALIBRATED, //陀螺仪传感器未校准 23 | ACC_UNCALIBRATED, //加速度传感器未校准 24 | MAG_UNCALIBRATED, //地磁传感器未校准 25 | TOF_UNCALIBRATED, //TOF传感器未校准 26 | ERROR_RESERVE6, 27 | ERROR_RESERVE7, 28 | ERROR_RESERVE8, 29 | ERROR_RESERVE9, 30 | SENSOR_HEAT_ERROR, //IMU传感器恒温不工作 31 | BMS_UNDETECTED, //未检测到电池管理系统 32 | CRITICAL_LOW_BATTERY, //严重低电量/电压 33 | ERROR_NUM 34 | }; 35 | 36 | //警告类型 37 | enum WARNNING_TYPE 38 | { 39 | WARNNING_RESERVE1, 40 | SYSTEM_INITIALIZING, //系统正在初始化 41 | WARNNING_RESERVE2, 42 | GYRO_NEED_CALIBRATED, //建议校准陀螺仪传感器 43 | ACC_NEED_CALIBRATED, //建议校准加速度传感器 44 | MAG_NEED_CALIBRATED, //建议校准地磁传感器 45 | WARNNING_RESERVE3, 46 | WARNNING_RESERVE4, 47 | WARNNING_RESERVE5, 48 | WARNNING_RESERVE6, 49 | MAG_DISTURBING, //地磁传感器受干扰 50 | WARNNING_RESERVE7, 51 | LOW_BATTERY, //低电量/电压 52 | LOW_BATTERY_FOR_RETURN, //电量/电压低于返航所需 53 | WARNNING_NUM 54 | }; 55 | 56 | 57 | void FaultDetectInit(void); 58 | void FaultDetectSetError(uint16_t error_type); 59 | void FaultDetectResetError(uint16_t error_type); 60 | void FaultDetectSetWarnning(uint16_t warnning_type); 61 | void FaultDetectResetWarnning(uint16_t warnning_type); 62 | uint8_t FaultDetectGetErrorStatus(uint16_t error_type); 63 | uint8_t FaultDetectGetWarnningStatus(uint16_t warnning_type); 64 | uint8_t* FaultDetectGetError(void); 65 | uint8_t* FaultDetectGetWarnning(void); 66 | 67 | #endif 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | -------------------------------------------------------------------------------- /Code Project/SRC/SYSTEM/flightStatus.h: -------------------------------------------------------------------------------- 1 | #ifndef __FLIGHTSTATUS_H__ 2 | #define __FLIGHTSTATUS_H__ 3 | 4 | #include "mathTool.h" 5 | 6 | //飞行状态 7 | enum 8 | { 9 | STANDBY, //待机 10 | TAKE_OFF, //起飞 11 | IN_AIR, //在空中 12 | LANDING, //降落 13 | FINISH_LANDING //降落完成 14 | }; 15 | 16 | //初始化状态 17 | enum 18 | { 19 | HEATING, //加热中 20 | HEAT_FINISH, //加热完成 21 | INIT_FINISH //初始化完成 (完成加速度零偏计算) 22 | }; 23 | 24 | //放置状态 25 | enum 26 | { 27 | STATIC, //静止 28 | MOTIONAL //运动 29 | }; 30 | 31 | //电机锁定状态 32 | enum 33 | { 34 | DISARMED, //上锁 35 | ARMED //解锁 36 | }; 37 | 38 | //水平方向控制状态 39 | enum 40 | { 41 | POS_HOLD, //悬停 42 | POS_CHANGED, //飞行 43 | POS_BRAKE, //刹车 44 | POS_BRAKE_FINISH //刹车完成 45 | }; 46 | 47 | //垂直方向控制状态 48 | enum 49 | { 50 | ALT_HOLD, //悬停 51 | ALT_CHANGED, //高度改变 52 | ALT_CHANGED_FINISH //高度改变完成 53 | }; 54 | 55 | //飞行模式 56 | enum 57 | { 58 | MANUAL = 0, //手动 (不带定高不带定点) 59 | SEMIAUTO, //半自动 (带定高不带定点) 60 | AUTO, //自动 (带定高带定点) 61 | SPORT, //运动模式 62 | COMMAND, //命令模式 (用于第三方控制) 63 | AUTOTAKEOFF, //自动起飞 64 | AUTOLAND, //自动降落 65 | RETURNTOHOME, //自动返航 66 | AUTOCIRCLE, //自动绕圈 67 | AUTOPILOT, //自动航线 68 | FOLLOWME //自动跟随 69 | }; 70 | 71 | void SystemInitCheck(void); 72 | 73 | void SetAltControlStatus(uint8_t status); 74 | uint8_t GetAltControlStatus(void); 75 | void SetPosControlStatus(uint8_t status); 76 | uint8_t GetPosControlStatus(void); 77 | 78 | bool SetArmedStatus(uint8_t status); 79 | uint8_t GetArmedStatus(void); 80 | 81 | void PlaceStausCheck(Vector3f_t gyro); 82 | uint8_t GetPlaceStatus(void); 83 | 84 | void SetInitStatus(uint8_t status); 85 | uint8_t GetInitStatus(void); 86 | uint32_t GetInitFinishTime(void); 87 | 88 | void SetFlightStatus(uint8_t status); 89 | uint8_t GetFlightStatus(void); 90 | 91 | void SetFlightMode(uint8_t mode); 92 | uint8_t GetFlightMode(void); 93 | 94 | void WindEstimate(void); 95 | float GetWindSpeed(void); 96 | float GetWindSpeedAcc(void); 97 | 98 | void SetFailSafeStatus(bool status); 99 | bool GetFailSafeStatus(void); 100 | 101 | #endif 102 | 103 | 104 | 105 | -------------------------------------------------------------------------------- /Code Project/SRC/SYSTEM/parameter.h: -------------------------------------------------------------------------------- 1 | #ifndef __PARAMETER_H__ 2 | #define __PARAMETER_H__ 3 | 4 | #include "board.h" 5 | 6 | enum PARAM_TYPE 7 | { 8 | PARAM_CHECK_NUM, 9 | PARAM_CHECK_SUM, 10 | /*******陀螺仪校准参数*********/ 11 | PARAM_GYRO_OFFSET_X, 12 | PARAM_GYRO_OFFSET_Y, 13 | PARAM_GYRO_OFFSET_Z, 14 | PARAM_GYRO_SCALE_X, 15 | PARAM_GYRO_SCALE_Y, 16 | PARAM_GYRO_SCALE_Z, 17 | /*******加速度校准参数*********/ 18 | PARAM_ACC_OFFSET_X, 19 | PARAM_ACC_OFFSET_Y, 20 | PARAM_ACC_OFFSET_Z, 21 | PARAM_ACC_SCALE_X, 22 | PARAM_ACC_SCALE_Y, 23 | PARAM_ACC_SCALE_Z, 24 | /*******磁力计校准参数*********/ 25 | PARAM_MAG_OFFSET_X, 26 | PARAM_MAG_OFFSET_Y, 27 | PARAM_MAG_OFFSET_Z, 28 | PARAM_MAG_SCALE_X, 29 | PARAM_MAG_SCALE_Y, 30 | PARAM_MAG_SCALE_Z, 31 | PARAM_MAG_EARTH_MAG, 32 | /*********水平校准参数*********/ 33 | PARAM_IMU_LEVEL_X, 34 | PARAM_IMU_LEVEL_Y, 35 | PARAM_IMU_LEVEL_Z, 36 | /*********姿态PID参数*********/ 37 | PARAM_PID_ATT_INNER_X_KP, 38 | PARAM_PID_ATT_INNER_X_KI, 39 | PARAM_PID_ATT_INNER_X_KD, 40 | PARAM_PID_ATT_INNER_Y_KP, 41 | PARAM_PID_ATT_INNER_Y_KI, 42 | PARAM_PID_ATT_INNER_Y_KD, 43 | PARAM_PID_ATT_INNER_Z_KP, 44 | PARAM_PID_ATT_INNER_Z_KI, 45 | PARAM_PID_ATT_INNER_Z_KD, 46 | PARAM_PID_ATT_OUTER_X_KP, 47 | PARAM_PID_ATT_OUTER_Y_KP, 48 | PARAM_PID_ATT_OUTER_Z_KP, 49 | /*********位置PID参数*********/ 50 | PARAM_PID_POS_INNER_X_KP, 51 | PARAM_PID_POS_INNER_X_KI, 52 | PARAM_PID_POS_INNER_X_KD, 53 | PARAM_PID_POS_INNER_Y_KP, 54 | PARAM_PID_POS_INNER_Y_KI, 55 | PARAM_PID_POS_INNER_Y_KD, 56 | PARAM_PID_POS_INNER_Z_KP, 57 | PARAM_PID_POS_INNER_Z_KI, 58 | PARAM_PID_POS_INNER_Z_KD, 59 | PARAM_PID_POS_OUTER_X_KP, 60 | PARAM_PID_POS_OUTER_Y_KP, 61 | PARAM_PID_POS_OUTER_Z_KP, 62 | /*********电调校准标志*********/ 63 | PARAM_ESC_CALI_FLAG, 64 | /******************************/ 65 | PARAM_NUM 66 | }; 67 | 68 | void ParamInit(void); 69 | void ParamSaveToFlash(void); 70 | void ParamUpdateData(uint16_t dataNum, const void * data); 71 | void ParamGetData(uint16_t dataNum, void *data, uint8_t length); 72 | const char* ParamGetString(uint8_t paramNum); 73 | 74 | #endif 75 | 76 | -------------------------------------------------------------------------------- /Code Project/SRC/TASK/TaskConfig.h: -------------------------------------------------------------------------------- 1 | /********************************************************************************************************** 2 | 天穹飞控 —— 致力于打造中国最好的多旋翼开源飞控 3 | Github: github.com/loveuav/BlueSkyFlightControl 4 | 技术讨论:bbs.loveuav.com/forum-68-1.html 5 | * @文件 TaskConfig.h 6 | * @说明 RTOS的任务配置文件,任务调度模式为抢占式,共有15个优先级(最多可设置为32) 7 | * @版本 V1.0 8 | * @作者 BlueSky 9 | * @网站 bbs.loveuav.com 10 | * @日期 2018.05 11 | **********************************************************************************************************/ 12 | #ifndef __TASKCONFIG_H__ 13 | #define __TASKCONFIG_H__ 14 | 15 | #include "FreeRTOS.h" 16 | #include "task.h" 17 | #include "queue.h" 18 | 19 | #include "board.h" 20 | #include "mathTool.h" 21 | 22 | #include "module_task.h" 23 | #include "sensor_task.h" 24 | #include "navigation_task.h" 25 | #include "control_task.h" 26 | #include "message_task.h" 27 | #include "log_task.h" 28 | 29 | //任务堆栈大小 30 | #define IMU_SENSOR_READ_TASK_STACK 256 31 | #define SENSOR_UPDATE_TASK_STACK 256 32 | #define IMU_DATA_PRETREAT_TASK_STACK 256 33 | #define OTHER_SENSOR_TASK_STACK 512 34 | #define NAVIGATION_TASK_STACK 512 35 | #define FLIGHT_STATUS_TASK_STACK 256 36 | #define FLIGHTCONTROL_TASK_STACK 256 37 | #define MESSAGE_TASK_STACK 512 38 | #define LOG_TASK_STACK 1024 39 | 40 | //任务优先级 41 | #define IMU_SENSOR_READ_TASK_PRIORITY 13 42 | #define IMU_DATA_PRETREAT_TASK_PRIORITY 12 43 | #define FLIGHTCONTROL_TASK_PRIORITY 10 44 | #define NAVIGATION_TASK_PRIORITY 11 45 | #define SENSOR_UPDATE_TASK_PRIORITY 8 46 | #define OTHER_SENSOR_TASK_PRIORITY 7 47 | #define MESSAGE_TASK_PRIORITY 6 48 | #define FLIGHT_STATUS_TASK_PRIORITY 5 49 | #define LOG_TASK_PRIORITY 3 50 | 51 | enum { 52 | GYRO_SENSOR_READ, 53 | ACC_SENSOR_READ, 54 | TEMP_SENSOR_READ, 55 | GYRO_DATA_PRETREAT, 56 | ACC_DATA_PRETREAT, 57 | GYRO_FOR_CONTROL, 58 | QUEUE_NUM 59 | }; 60 | 61 | extern QueueHandle_t messageQueue[QUEUE_NUM]; 62 | 63 | #endif 64 | -------------------------------------------------------------------------------- /Code Project/SRC/TASK/control_task.c: -------------------------------------------------------------------------------- 1 | /********************************************************************************************************** 2 | 天穹飞控 —— 致力于打造中国最好的多旋翼开源飞控 3 | Github: github.com/loveuav/BlueSkyFlightControl 4 | 技术讨论:bbs.loveuav.com/forum-68-1.html 5 | * @文件 control_task.c 6 | * @说明 飞行控制相关任务 7 | * @版本 V1.0 8 | * @作者 BlueSky 9 | * @网站 bbs.loveuav.com 10 | * @日期 2018.05 11 | **********************************************************************************************************/ 12 | #include "TaskConfig.h" 13 | 14 | #include "flightControl.h" 15 | #include "userControl.h" 16 | #include "missionControl.h" 17 | #include "commandControl.h" 18 | #include "safeControl.h" 19 | #include "rc.h" 20 | 21 | xTaskHandle flightControlTask; 22 | 23 | /********************************************************************************************************** 24 | *函 数 名: vFlightControlTask 25 | *功能说明: 飞行控制相关任务 26 | *形 参: 无 27 | *返 回 值: 无 28 | **********************************************************************************************************/ 29 | portTASK_FUNCTION(vFlightControlTask, pvParameters) 30 | { 31 | Vector3f_t* gyro; 32 | static uint32_t count = 0; 33 | 34 | //遥控相关功能初始化 35 | RcInit(); 36 | 37 | //控制参数初始化 38 | FlightControlInit(); 39 | 40 | for(;;) 41 | { 42 | //从消息队列中获取数据 43 | xQueueReceive(messageQueue[GYRO_FOR_CONTROL], &gyro, (3 / portTICK_RATE_MS)); 44 | 45 | //100Hz 46 | if(count % 10 == 0) 47 | { 48 | //遥控器各通道数据及失控检测 49 | RcCheck(); 50 | 51 | //安全保护控制 52 | SafeControl(); 53 | } 54 | 55 | //200Hz 56 | if(count % 5 == 0) 57 | { 58 | //位置外环控制 59 | PositionOuterControl(); 60 | } 61 | 62 | //500Hz 63 | if(count % 2 == 0) 64 | { 65 | //用户控制模式下的操控逻辑处理 66 | UserControl(); 67 | 68 | //自主控制任务实现(自动起飞、自动降落、自动返航、自动航线等) 69 | MissionControl(); 70 | 71 | //位置内环控制 72 | PositionInnerControl(); 73 | 74 | //姿态外环控制 75 | AttitudeOuterControl(); 76 | 77 | //高度外环控制 78 | AltitudeOuterControl(); 79 | } 80 | 81 | //飞行内环控制,包括姿态内环和高度内环 82 | FlightControlInnerLoop(*gyro); 83 | 84 | count++; 85 | } 86 | } 87 | 88 | /********************************************************************************************************** 89 | *函 数 名: ControlTaskCreate 90 | *功能说明: 控制相关任务创建 91 | *形 参: 无 92 | *返 回 值: 无 93 | **********************************************************************************************************/ 94 | void ControlTaskCreate(void) 95 | { 96 | xTaskCreate(vFlightControlTask, "flightControl", FLIGHTCONTROL_TASK_STACK, NULL, FLIGHTCONTROL_TASK_PRIORITY, &flightControlTask); 97 | } 98 | 99 | /********************************************************************************************************** 100 | *函 数 名: GetFlightControlTaskStackRemain 101 | *功能说明: 获取任务堆栈使用剩余 102 | *形 参: 无 103 | *返 回 值: 无 104 | **********************************************************************************************************/ 105 | int16_t GetFlightControlTaskStackRemain(void) 106 | { 107 | return uxTaskGetStackHighWaterMark(flightControlTask); 108 | } 109 | 110 | 111 | 112 | 113 | -------------------------------------------------------------------------------- /Code Project/SRC/TASK/control_task.h: -------------------------------------------------------------------------------- 1 | #ifndef __CONTROL_TASK_H__ 2 | #define __CONTROL_TASK_H__ 3 | 4 | void ControlTaskCreate(void); 5 | 6 | int16_t GetFlightControlTaskStackRemain(void); 7 | 8 | #endif 9 | 10 | 11 | 12 | -------------------------------------------------------------------------------- /Code Project/SRC/TASK/log_task.c: -------------------------------------------------------------------------------- 1 | /********************************************************************************************************** 2 | 天穹飞控 —— 致力于打造中国最好的多旋翼开源飞控 3 | Github: github.com/loveuav/BlueSkyFlightControl 4 | 技术讨论:bbs.loveuav.com/forum-68-1.html 5 | * @文件 log_task.c 6 | * @说明 飞行日志相关任务 7 | * @版本 V1.0 8 | * @作者 BlueSky 9 | * @网站 bbs.loveuav.com 10 | * @日期 2018.08 11 | **********************************************************************************************************/ 12 | #include "TaskConfig.h" 13 | 14 | #include "logger.h" 15 | 16 | xTaskHandle logTask; 17 | 18 | /********************************************************************************************************** 19 | *函 数 名: vLogTask 20 | *功能说明: 飞行日志任务 21 | *形 参: 无 22 | *返 回 值: 无 23 | **********************************************************************************************************/ 24 | portTASK_FUNCTION(vLogTask, pvParameters) 25 | { 26 | portTickType xLastWakeTime; 27 | 28 | //飞行日志初始化 29 | LoggerInit(); 30 | 31 | xLastWakeTime = xTaskGetTickCount(); 32 | for(;;) 33 | { 34 | //记录飞行日志 35 | LoggerLoop(); 36 | 37 | vTaskDelayUntil(&xLastWakeTime, ((1000 / LOG_RATE) / portTICK_RATE_MS)); 38 | } 39 | } 40 | 41 | /********************************************************************************************************** 42 | *函 数 名: LogTaskCreate 43 | *功能说明: 飞行日志任务创建 44 | *形 参: 无 45 | *返 回 值: 无 46 | **********************************************************************************************************/ 47 | void LogTaskCreate(void) 48 | { 49 | xTaskCreate(vLogTask, "log", LOG_TASK_STACK, NULL, LOG_TASK_PRIORITY, &logTask); 50 | } 51 | 52 | /********************************************************************************************************** 53 | *函 数 名: GetLogTaskStackRemain 54 | *功能说明: 获取任务堆栈使用剩余 55 | *形 参: 无 56 | *返 回 值: 无 57 | **********************************************************************************************************/ 58 | int16_t GetLogTaskStackRemain(void) 59 | { 60 | return uxTaskGetStackHighWaterMark(logTask); 61 | } 62 | 63 | 64 | -------------------------------------------------------------------------------- /Code Project/SRC/TASK/log_task.h: -------------------------------------------------------------------------------- 1 | #ifndef __LOG_TASK_H__ 2 | #define __LOG_TASK_H__ 3 | 4 | void LogTaskCreate(void); 5 | 6 | int16_t GetLogTaskStackRemain(void); 7 | 8 | #endif 9 | 10 | -------------------------------------------------------------------------------- /Code Project/SRC/TASK/messageQueue.c: -------------------------------------------------------------------------------- 1 | /********************************************************************************************************** 2 | 天穹飞控 —— 致力于打造中国最好的多旋翼开源飞控 3 | Github: github.com/loveuav/BlueSkyFlightControl 4 | 技术讨论:bbs.loveuav.com/forum-68-1.html 5 | * @文件 messageQueue.c 6 | * @说明 消息队列,主要用于对数据传递实时性要求较高的任务间通信 7 | * @版本 V1.0 8 | * @作者 BlueSky 9 | * @网站 bbs.loveuav.com 10 | * @日期 2018.05 11 | **********************************************************************************************************/ 12 | #include "messageQueue.h" 13 | 14 | //声明消息队列句柄 15 | QueueHandle_t messageQueue[QUEUE_NUM]; 16 | 17 | /********************************************************************************************************** 18 | *函 数 名: MessageQueueCreate 19 | *功能说明: 消息队列创建 20 | *形 参: 无 21 | *返 回 值: 无 22 | **********************************************************************************************************/ 23 | void MessageQueueCreate(void) 24 | { 25 | messageQueue[ACC_SENSOR_READ] = xQueueCreate(2, sizeof(Vector3f_t *)); 26 | messageQueue[GYRO_SENSOR_READ] = xQueueCreate(2, sizeof(Vector3f_t *)); 27 | messageQueue[TEMP_SENSOR_READ] = xQueueCreate(2, sizeof(float *)); 28 | 29 | messageQueue[GYRO_DATA_PRETREAT] = xQueueCreate(2, sizeof(Vector3f_t *)); 30 | messageQueue[ACC_DATA_PRETREAT] = xQueueCreate(2, sizeof(Vector3f_t *)); 31 | messageQueue[GYRO_FOR_CONTROL] = xQueueCreate(2, sizeof(Vector3f_t *)); 32 | } 33 | 34 | 35 | 36 | 37 | 38 | 39 | -------------------------------------------------------------------------------- /Code Project/SRC/TASK/messageQueue.h: -------------------------------------------------------------------------------- 1 | #ifndef __MESSAGE_QUEUE_H__ 2 | #define __MESSAGE_QUEUE_H__ 3 | 4 | #include "TaskConfig.h" 5 | 6 | void MessageQueueCreate(void); 7 | 8 | #endif 9 | 10 | -------------------------------------------------------------------------------- /Code Project/SRC/TASK/message_task.c: -------------------------------------------------------------------------------- 1 | /********************************************************************************************************** 2 | 天穹飞控 —— 致力于打造中国最好的多旋翼开源飞控 3 | Github: github.com/loveuav/BlueSkyFlightControl 4 | 技术讨论:bbs.loveuav.com/forum-68-1.html 5 | * @文件 message_task.c 6 | * @说明 飞控数据通信相关任务 7 | * @版本 V1.0 8 | * @作者 BlueSky 9 | * @网站 bbs.loveuav.com 10 | * @日期 2018.06 11 | **********************************************************************************************************/ 12 | #include "TaskConfig.h" 13 | 14 | #include "message.h" 15 | 16 | xTaskHandle messageTask; 17 | 18 | /********************************************************************************************************** 19 | *函 数 名: vMessageTask 20 | *功能说明: 数据通信任务 21 | *形 参: 无 22 | *返 回 值: 无 23 | **********************************************************************************************************/ 24 | portTASK_FUNCTION(vMessageTask, pvParameters) 25 | { 26 | portTickType xLastWakeTime; 27 | 28 | //飞控数据通信初始化 29 | MessageInit(); 30 | 31 | xLastWakeTime = xTaskGetTickCount(); 32 | for(;;) 33 | { 34 | //发送飞控数据 35 | MessageSendLoop(); 36 | 37 | vTaskDelayUntil(&xLastWakeTime, ((1000 / MAX_SEND_FREQ) / portTICK_RATE_MS)); 38 | } 39 | } 40 | 41 | /********************************************************************************************************** 42 | *函 数 名: MessageTaskCreate 43 | *功能说明: 数据通信任务创建 44 | *形 参: 无 45 | *返 回 值: 无 46 | **********************************************************************************************************/ 47 | void MessageTaskCreate(void) 48 | { 49 | xTaskCreate(vMessageTask, "message", MESSAGE_TASK_STACK, NULL, MESSAGE_TASK_PRIORITY, &messageTask); 50 | } 51 | 52 | /********************************************************************************************************** 53 | *函 数 名: GetMessageTaskStackRemain 54 | *功能说明: 获取任务堆栈使用剩余 55 | *形 参: 无 56 | *返 回 值: 无 57 | **********************************************************************************************************/ 58 | int16_t GetMessageTaskStackRemain(void) 59 | { 60 | return uxTaskGetStackHighWaterMark(messageTask); 61 | } 62 | 63 | 64 | -------------------------------------------------------------------------------- /Code Project/SRC/TASK/message_task.h: -------------------------------------------------------------------------------- 1 | #ifndef __MESSAGE_TASK_H__ 2 | #define __MESSAGE_TASK_H__ 3 | 4 | void MessageTaskCreate(void); 5 | 6 | int16_t GetMessageTaskStackRemain(void); 7 | 8 | #endif 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /Code Project/SRC/TASK/module_task.h: -------------------------------------------------------------------------------- 1 | #ifndef __MODULE_TASK_H__ 2 | #define __MODULE_TASK_H__ 3 | 4 | void ModuleTaskCreate(void); 5 | int16_t GetImuSensorReadTaskStackRemain(void); 6 | int16_t GetSensorUpdateTaskStackRemain(void); 7 | 8 | #endif 9 | 10 | 11 | -------------------------------------------------------------------------------- /Code Project/SRC/TASK/navigation_task.h: -------------------------------------------------------------------------------- 1 | #ifndef __NAVIGATION_TASK_H__ 2 | #define __NAVIGATION_TASK_H__ 3 | 4 | 5 | void NavigationTaskCreate(void); 6 | 7 | int16_t GetNavigationTaskStackRemain(void); 8 | int16_t GetFlightStatusTaskStackRemain(void); 9 | 10 | #endif 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /Code Project/SRC/TASK/sensor_task.h: -------------------------------------------------------------------------------- 1 | #ifndef __SENSOR_TASK_H__ 2 | #define __SENSOR_TASK_H__ 3 | 4 | void SensorTaskCreate(void); 5 | 6 | int16_t GetImuDataPreTreatTaskStackRemain(void); 7 | int16_t GetOtherSensorTaskStackRemain(void); 8 | 9 | #endif 10 | 11 | 12 | -------------------------------------------------------------------------------- /Code Project/USB_DEVICE/App/usb_device.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file : usb_device.c 5 | * @version : v1.0_Cube 6 | * @brief : This file implements the USB Device 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | *

© Copyright (c) 2021 STMicroelectronics. 11 | * All rights reserved.

12 | * 13 | * This software component is licensed by ST under Ultimate Liberty license 14 | * SLA0044, the "License"; You may not use this file except in compliance with 15 | * the License. You may obtain a copy of the License at: 16 | * www.st.com/SLA0044 17 | * 18 | ****************************************************************************** 19 | */ 20 | /* USER CODE END Header */ 21 | 22 | /* Includes ------------------------------------------------------------------*/ 23 | 24 | #include "usb_device.h" 25 | #include "usbd_core.h" 26 | #include "usbd_desc.h" 27 | #include "usbd_cdc.h" 28 | #include "usbd_cdc_if.h" 29 | 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | /* USER CODE BEGIN PV */ 35 | /* Private variables ---------------------------------------------------------*/ 36 | 37 | /* USER CODE END PV */ 38 | 39 | /* USER CODE BEGIN PFP */ 40 | /* Private function prototypes -----------------------------------------------*/ 41 | 42 | /* USER CODE END PFP */ 43 | 44 | /* USB Device Core handle declaration. */ 45 | USBD_HandleTypeDef hUsbDeviceFS; 46 | 47 | /* 48 | * -- Insert your variables declaration here -- 49 | */ 50 | /* USER CODE BEGIN 0 */ 51 | 52 | /* USER CODE END 0 */ 53 | 54 | /* 55 | * -- Insert your external function declaration here -- 56 | */ 57 | /* USER CODE BEGIN 1 */ 58 | 59 | /* USER CODE END 1 */ 60 | 61 | /** 62 | * Init USB device Library, add supported class and start the library 63 | * @retval None 64 | */ 65 | void MX_USB_DEVICE_Init(void) 66 | { 67 | /* USER CODE BEGIN USB_DEVICE_Init_PreTreatment */ 68 | 69 | /* USER CODE END USB_DEVICE_Init_PreTreatment */ 70 | 71 | /* Init Device Library, add supported class and start the library. */ 72 | if (USBD_Init(&hUsbDeviceFS, &FS_Desc, DEVICE_FS) != USBD_OK) 73 | { 74 | Error_Handler(); 75 | } 76 | if (USBD_RegisterClass(&hUsbDeviceFS, &USBD_CDC) != USBD_OK) 77 | { 78 | Error_Handler(); 79 | } 80 | if (USBD_CDC_RegisterInterface(&hUsbDeviceFS, &USBD_Interface_fops_FS) != USBD_OK) 81 | { 82 | Error_Handler(); 83 | } 84 | if (USBD_Start(&hUsbDeviceFS) != USBD_OK) 85 | { 86 | Error_Handler(); 87 | } 88 | 89 | /* USER CODE BEGIN USB_DEVICE_Init_PostTreatment */ 90 | HAL_PWREx_EnableUSBVoltageDetector(); 91 | 92 | /* USER CODE END USB_DEVICE_Init_PostTreatment */ 93 | } 94 | 95 | /** 96 | * @} 97 | */ 98 | 99 | /** 100 | * @} 101 | */ 102 | 103 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 104 | -------------------------------------------------------------------------------- /Code Project/USB_DEVICE/App/usb_device.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file : usb_device.h 5 | * @version : v1.0_Cube 6 | * @brief : Header for usb_device.c file. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | *

© Copyright (c) 2021 STMicroelectronics. 11 | * All rights reserved.

12 | * 13 | * This software component is licensed by ST under Ultimate Liberty license 14 | * SLA0044, the "License"; You may not use this file except in compliance with 15 | * the License. You may obtain a copy of the License at: 16 | * www.st.com/SLA0044 17 | * 18 | ****************************************************************************** 19 | */ 20 | /* USER CODE END Header */ 21 | 22 | /* Define to prevent recursive inclusion -------------------------------------*/ 23 | #ifndef __USB_DEVICE__H__ 24 | #define __USB_DEVICE__H__ 25 | 26 | #ifdef __cplusplus 27 | extern "C" { 28 | #endif 29 | 30 | /* Includes ------------------------------------------------------------------*/ 31 | #include "stm32h7xx.h" 32 | #include "stm32h7xx_hal.h" 33 | #include "usbd_def.h" 34 | 35 | /* USER CODE BEGIN INCLUDE */ 36 | 37 | /* USER CODE END INCLUDE */ 38 | 39 | /** @addtogroup USBD_OTG_DRIVER 40 | * @{ 41 | */ 42 | 43 | /** @defgroup USBD_DEVICE USBD_DEVICE 44 | * @brief Device file for Usb otg low level driver. 45 | * @{ 46 | */ 47 | 48 | /** @defgroup USBD_DEVICE_Exported_Variables USBD_DEVICE_Exported_Variables 49 | * @brief Public variables. 50 | * @{ 51 | */ 52 | 53 | /* Private variables ---------------------------------------------------------*/ 54 | /* USER CODE BEGIN PV */ 55 | 56 | /* USER CODE END PV */ 57 | 58 | /* Private function prototypes -----------------------------------------------*/ 59 | /* USER CODE BEGIN PFP */ 60 | 61 | /* USER CODE END PFP */ 62 | 63 | /* 64 | * -- Insert your variables declaration here -- 65 | */ 66 | /* USER CODE BEGIN VARIABLES */ 67 | 68 | /* USER CODE END VARIABLES */ 69 | /** 70 | * @} 71 | */ 72 | 73 | /** @defgroup USBD_DEVICE_Exported_FunctionsPrototype USBD_DEVICE_Exported_FunctionsPrototype 74 | * @brief Declaration of public functions for Usb device. 75 | * @{ 76 | */ 77 | 78 | /** USB Device initialization function. */ 79 | void MX_USB_DEVICE_Init(void); 80 | 81 | /* 82 | * -- Insert functions declaration here -- 83 | */ 84 | /* USER CODE BEGIN FD */ 85 | 86 | /* USER CODE END FD */ 87 | /** 88 | * @} 89 | */ 90 | 91 | /** 92 | * @} 93 | */ 94 | 95 | /** 96 | * @} 97 | */ 98 | 99 | #ifdef __cplusplus 100 | } 101 | #endif 102 | 103 | #endif /* __USB_DEVICE__H__ */ 104 | 105 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 106 | -------------------------------------------------------------------------------- /Code Project/USB_DEVICE/App/usbd_cdc_if.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file : usbd_cdc_if.h 5 | * @version : v1.0_Cube 6 | * @brief : Header for usbd_cdc_if.c file. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | *

© Copyright (c) 2021 STMicroelectronics. 11 | * All rights reserved.

12 | * 13 | * This software component is licensed by ST under Ultimate Liberty license 14 | * SLA0044, the "License"; You may not use this file except in compliance with 15 | * the License. You may obtain a copy of the License at: 16 | * www.st.com/SLA0044 17 | * 18 | ****************************************************************************** 19 | */ 20 | /* USER CODE END Header */ 21 | 22 | /* Define to prevent recursive inclusion -------------------------------------*/ 23 | #ifndef __USBD_CDC_IF_H__ 24 | #define __USBD_CDC_IF_H__ 25 | 26 | #ifdef __cplusplus 27 | extern "C" { 28 | #endif 29 | 30 | /* Includes ------------------------------------------------------------------*/ 31 | #include "usbd_cdc.h" 32 | 33 | /* USER CODE BEGIN INCLUDE */ 34 | 35 | /* USER CODE END INCLUDE */ 36 | 37 | /** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY 38 | * @brief For Usb device. 39 | * @{ 40 | */ 41 | 42 | /** @defgroup USBD_CDC_IF USBD_CDC_IF 43 | * @brief Usb VCP device module 44 | * @{ 45 | */ 46 | 47 | /** @defgroup USBD_CDC_IF_Exported_Defines USBD_CDC_IF_Exported_Defines 48 | * @brief Defines. 49 | * @{ 50 | */ 51 | /* USER CODE BEGIN EXPORTED_DEFINES */ 52 | /* Define size for the receive and transmit buffer over CDC */ 53 | /* It's up to user to redefine and/or remove those define */ 54 | #define APP_RX_DATA_SIZE 2048 55 | #define APP_TX_DATA_SIZE 2048 56 | 57 | /* USER CODE END EXPORTED_DEFINES */ 58 | 59 | /** 60 | * @} 61 | */ 62 | 63 | /** @defgroup USBD_CDC_IF_Exported_Types USBD_CDC_IF_Exported_Types 64 | * @brief Types. 65 | * @{ 66 | */ 67 | 68 | /* USER CODE BEGIN EXPORTED_TYPES */ 69 | 70 | /* USER CODE END EXPORTED_TYPES */ 71 | 72 | /** 73 | * @} 74 | */ 75 | 76 | /** @defgroup USBD_CDC_IF_Exported_Macros USBD_CDC_IF_Exported_Macros 77 | * @brief Aliases. 78 | * @{ 79 | */ 80 | 81 | /* USER CODE BEGIN EXPORTED_MACRO */ 82 | 83 | /* USER CODE END EXPORTED_MACRO */ 84 | 85 | /** 86 | * @} 87 | */ 88 | 89 | /** @defgroup USBD_CDC_IF_Exported_Variables USBD_CDC_IF_Exported_Variables 90 | * @brief Public variables. 91 | * @{ 92 | */ 93 | 94 | /** CDC Interface callback. */ 95 | extern USBD_CDC_ItfTypeDef USBD_Interface_fops_FS; 96 | 97 | /* USER CODE BEGIN EXPORTED_VARIABLES */ 98 | 99 | /* USER CODE END EXPORTED_VARIABLES */ 100 | 101 | /** 102 | * @} 103 | */ 104 | 105 | /** @defgroup USBD_CDC_IF_Exported_FunctionsPrototype USBD_CDC_IF_Exported_FunctionsPrototype 106 | * @brief Public functions declaration. 107 | * @{ 108 | */ 109 | 110 | uint8_t CDC_Transmit_FS(uint8_t* Buf, uint16_t Len); 111 | 112 | /* USER CODE BEGIN EXPORTED_FUNCTIONS */ 113 | 114 | /* USER CODE END EXPORTED_FUNCTIONS */ 115 | 116 | /** 117 | * @} 118 | */ 119 | 120 | /** 121 | * @} 122 | */ 123 | 124 | /** 125 | * @} 126 | */ 127 | 128 | #ifdef __cplusplus 129 | } 130 | #endif 131 | 132 | #endif /* __USBD_CDC_IF_H__ */ 133 | 134 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 135 | -------------------------------------------------------------------------------- /Code Project/USB_DEVICE/App/usbd_desc.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file : usbd_desc.c 5 | * @version : v1.0_Cube 6 | * @brief : Header for usbd_conf.c file. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | *

© Copyright (c) 2021 STMicroelectronics. 11 | * All rights reserved.

12 | * 13 | * This software component is licensed by ST under Ultimate Liberty license 14 | * SLA0044, the "License"; You may not use this file except in compliance with 15 | * the License. You may obtain a copy of the License at: 16 | * www.st.com/SLA0044 17 | * 18 | ****************************************************************************** 19 | */ 20 | /* USER CODE END Header */ 21 | /* Define to prevent recursive inclusion -------------------------------------*/ 22 | #ifndef __USBD_DESC__C__ 23 | #define __USBD_DESC__C__ 24 | 25 | #ifdef __cplusplus 26 | extern "C" { 27 | #endif 28 | 29 | /* Includes ------------------------------------------------------------------*/ 30 | #include "usbd_def.h" 31 | 32 | /* USER CODE BEGIN INCLUDE */ 33 | 34 | /* USER CODE END INCLUDE */ 35 | 36 | /** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY 37 | * @{ 38 | */ 39 | 40 | /** @defgroup USBD_DESC USBD_DESC 41 | * @brief Usb device descriptors module. 42 | * @{ 43 | */ 44 | 45 | /** @defgroup USBD_DESC_Exported_Constants USBD_DESC_Exported_Constants 46 | * @brief Constants. 47 | * @{ 48 | */ 49 | #define DEVICE_ID1 (UID_BASE) 50 | #define DEVICE_ID2 (UID_BASE + 0x4) 51 | #define DEVICE_ID3 (UID_BASE + 0x8) 52 | 53 | #define USB_SIZ_STRING_SERIAL 0x1A 54 | 55 | /* USER CODE BEGIN EXPORTED_CONSTANTS */ 56 | 57 | /* USER CODE END EXPORTED_CONSTANTS */ 58 | 59 | /** 60 | * @} 61 | */ 62 | 63 | /** @defgroup USBD_DESC_Exported_Defines USBD_DESC_Exported_Defines 64 | * @brief Defines. 65 | * @{ 66 | */ 67 | 68 | /* USER CODE BEGIN EXPORTED_DEFINES */ 69 | 70 | /* USER CODE END EXPORTED_DEFINES */ 71 | 72 | /** 73 | * @} 74 | */ 75 | 76 | /** @defgroup USBD_DESC_Exported_TypesDefinitions USBD_DESC_Exported_TypesDefinitions 77 | * @brief Types. 78 | * @{ 79 | */ 80 | 81 | /* USER CODE BEGIN EXPORTED_TYPES */ 82 | 83 | /* USER CODE END EXPORTED_TYPES */ 84 | 85 | /** 86 | * @} 87 | */ 88 | 89 | /** @defgroup USBD_DESC_Exported_Macros USBD_DESC_Exported_Macros 90 | * @brief Aliases. 91 | * @{ 92 | */ 93 | 94 | /* USER CODE BEGIN EXPORTED_MACRO */ 95 | 96 | /* USER CODE END EXPORTED_MACRO */ 97 | 98 | /** 99 | * @} 100 | */ 101 | 102 | /** @defgroup USBD_DESC_Exported_Variables USBD_DESC_Exported_Variables 103 | * @brief Public variables. 104 | * @{ 105 | */ 106 | 107 | /** Descriptor for the Usb device. */ 108 | extern USBD_DescriptorsTypeDef FS_Desc; 109 | 110 | /* USER CODE BEGIN EXPORTED_VARIABLES */ 111 | 112 | /* USER CODE END EXPORTED_VARIABLES */ 113 | 114 | /** 115 | * @} 116 | */ 117 | 118 | /** @defgroup USBD_DESC_Exported_FunctionsPrototype USBD_DESC_Exported_FunctionsPrototype 119 | * @brief Public functions declaration. 120 | * @{ 121 | */ 122 | 123 | /* USER CODE BEGIN EXPORTED_FUNCTIONS */ 124 | 125 | /* USER CODE END EXPORTED_FUNCTIONS */ 126 | 127 | /** 128 | * @} 129 | */ 130 | 131 | /** 132 | * @} 133 | */ 134 | 135 | /** 136 | * @} 137 | */ 138 | 139 | #ifdef __cplusplus 140 | } 141 | #endif 142 | 143 | #endif /* __USBD_DESC__C__ */ 144 | 145 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 146 | -------------------------------------------------------------------------------- /Object Task/README.md: -------------------------------------------------------------------------------- 1 | # 文件说明 2 | 3 | - `protocol.py`:协议 4 | - `vision.py`:视觉 5 | - `mission.py`:任务 -------------------------------------------------------------------------------- /Object Task/pid.py: -------------------------------------------------------------------------------- 1 | import time 2 | 3 | class PID(object): 4 | 5 | def __init__(self, P, I, D, SetPoint): 6 | self.Kp = P 7 | self.Ki = I 8 | self.Kd = D 9 | self.sample_time = 0.00 10 | self.current_time = time.time() 11 | self.last_time = self.current_time 12 | self.clear() 13 | self.SetPoint = SetPoint 14 | 15 | def clear(self): 16 | self.SetPoint = 0.0 17 | self.PTerm = 0.0 18 | self.ITerm = 0.0 19 | self.DTerm = 0.0 20 | self.last_error = 0.0 21 | self.int_error = 0.0 22 | self.output = 0.0 23 | 24 | def update(self, feedback_value): 25 | error = self.SetPoint - feedback_value 26 | self.current_time = time.time() 27 | delta_time = self.current_time - self.last_time 28 | delta_error = error - self.last_error 29 | if (delta_time >= self.sample_time): 30 | self.PTerm = self.Kp * error#比例 31 | self.ITerm += error * delta_time#积分 32 | self.DTerm = 0.0 33 | if delta_time > 0: 34 | self.DTerm = delta_error / delta_time#微分 35 | self.last_time = self.current_time 36 | self.last_error = error 37 | self.output = self.PTerm + (self.Ki * self.ITerm) + (self.Kd * self.DTerm) 38 | return self.output 39 | else: 40 | return False 41 | 42 | def setSampleTime(self, sample_time): 43 | self.sample_time = sample_time 44 | 45 | def setSetPoint(self, SetPoint): 46 | self.SetPoint = SetPoint 47 | 48 | def clip(value, limit): 49 | if abs(value)>limit: 50 | if value>0: 51 | return limit 52 | else: 53 | return -limit 54 | else: 55 | return value -------------------------------------------------------------------------------- /Object Task/protocol_demo.py: -------------------------------------------------------------------------------- 1 | from protocol import protocol 2 | 3 | 4 | if __name__ == "__main__": 5 | ptcl = protocol() 6 | 7 | ptcl.clear() 8 | ptcl.set_motion('disarm') 9 | ptcl.send(need_check_sum = False) 10 | 11 | ptcl.clear() 12 | ptcl.set_motion('autoTakeOff') 13 | ptcl.send(need_check_sum = False) 14 | 15 | ptcl.clear() 16 | ptcl.set_vel(x=0x1111, y=0x2222, z=0x3333) 17 | ptcl.send(need_check_sum = False) 18 | 19 | ptcl.clear() 20 | ptcl.set_pos(roll=0x1111, pitch=0x2222, yaw=0x3333) 21 | ptcl.send(need_check_sum = False) 22 | 23 | ptcl.clear() 24 | ptcl.set_motion('autoLand') 25 | ptcl.send(need_check_sum = False) -------------------------------------------------------------------------------- /Object Task/test_camera.py: -------------------------------------------------------------------------------- 1 | import cv2 2 | 3 | def imshow_ssh(frame): 4 | height, width = frame.shape[:2] 5 | size = 320/width 6 | cv2.imshow("image", cv2.resize(frame, None, fx = size, fy = size)) 7 | cv2.waitKey(10) 8 | 9 | def get_camera_para(capture): 10 | print( 11 | 'width:', capture.get(cv2.CAP_PROP_FRAME_WIDTH), 12 | 'height:', capture.get(cv2.CAP_PROP_FRAME_HEIGHT), 13 | 'fps:', capture.get(cv2.CAP_PROP_FPS), 14 | 'brightness:', capture.get(cv2.CAP_PROP_BRIGHTNESS), 15 | 'contrast:', capture.get(cv2.CAP_PROP_CONTRAST), 16 | 'saturation:', capture.get(cv2.CAP_PROP_SATURATION), 17 | 'hue:', capture.get(cv2.CAP_PROP_HUE), 18 | 'exposure:', capture.get(cv2.CAP_PROP_EXPOSURE), 19 | '', capture.get(cv2.CAP_PROP_FRAME_COUNT), 20 | ) 21 | 22 | if __name__ == "__main__": 23 | cam = cv2.VideoCapture(1) 24 | 25 | if not cam.isOpened(): 26 | print("Error: Can't open camera.") 27 | else: 28 | cam.set(cv2.CAP_PROP_FPS, 30) 29 | get_camera_para(cam) 30 | while True: 31 | ret, frame = cam.read() 32 | imshow_ssh(frame) 33 | print(frame.shape) 34 | -------------------------------------------------------------------------------- /Object Task/test_math.py: -------------------------------------------------------------------------------- 1 | class AverageFilter(object): 2 | # 平均滤波 3 | # 用法: 4 | # 1. 初始化时写入需要滤波长度 5 | # 2. 用 .append() 添加新数据 6 | # 3. 用 .calc() 计算平均值 7 | def __init__(self, length): 8 | self.length = length 9 | self.index = 0 10 | self.values = [] 11 | 12 | def clear(self): 13 | self.index = 0 14 | self.values = [] 15 | 16 | def append(self, value): 17 | if len(self.values) < self.length: 18 | self.values.append(value) 19 | self.index += 1 20 | self.index %= self.length 21 | else: 22 | self.values[self.index] = value 23 | self.index += 1 24 | self.index %= self.length 25 | 26 | def calc(self): 27 | if len(self.values) != 0: 28 | sum = 0 29 | for i in self.values: 30 | sum += i 31 | avg = sum/len(self.values) 32 | else: 33 | avg = 0 34 | return avg 35 | 36 | def has(self, value): 37 | return value in self.values 38 | 39 | filter = AverageFilter(3) 40 | while(True): 41 | value = bool(int(input('Get Input:'))) 42 | filter.append(value) 43 | print(filter.has(False)) -------------------------------------------------------------------------------- /Object Task/test_serial.py: -------------------------------------------------------------------------------- 1 | import wiringpi 2 | 3 | serial = wiringpi.serialOpen('/dev/ttyUSB0', 9600) 4 | wiringpi.serialPuts(serial, 'Send:') 5 | test = 0xaa 6 | wiringpi.serialPutchar(serial, test) 7 | wiringpi.serialPuts(serial, '\n') 8 | wiringpi.serialClose(serial) -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # 开源飞控-天穹飞控V2原作者梦阳 2 | 3 | ![如果图片无法显示请访问https://gitee.com/makermare](%E9%A3%9E%E8%A1%8C%E4%BB%BB%E5%8A%A1%E7%8A%B6%E6%80%81%E5%9B%BE.png) 4 | 5 | #### 介绍 6 | # BlueSkyFlightControl 7 | 算法上基于的非线性卡尔曼滤波、梯度下降预估最小二乘法的改版, 8 | 支持导航、光流、激光定高。 9 | 10 | 本项目相对原始天穹飞控,有如下主要变化: 11 | 1. 主控芯片换为 STM32H743VI。 12 | 2. 增加了一些传感器驱动和光流、激光高度计传感器。 13 | 3. 增加了外部控制飞行的Python脚本,支持视觉识别。 14 | 4. 增加了代码的文档。 15 | 16 | #### 软件架构 17 | 软件架构说明 18 | ![如果图片无法显示请访问https://gitee.com/makermare](%E9%A3%9E%E6%8E%A7%E4%BB%BB%E5%8A%A1%E5%92%8C%E6%8E%A7%E5%88%B6%E4%BB%BB%E5%8A%A1%E6%B5%81%E7%A8%8B%E5%9B%BE.png) 19 | 20 | ![如果图片无法显示请访问https://gitee.com/makermare](%E9%A3%9E%E8%A1%8C%E7%8A%B6%E6%80%81%E6%9B%B4%E6%96%B0%EF%BC%88%E5%8E%9F%E5%A4%A9%E7%A9%B9%E4%BB%A3%E7%A0%81%EF%BC%89.png) 21 | 22 | #### 安装教程 23 | 24 | 1. xxxx 25 | 2. xxxx 26 | 3. xxxx 27 | 28 | #### 使用说明 29 | 30 | 1. xxxx 31 | 2. xxxx 32 | 3. xxxx 33 | 34 | #### 参与贡献 35 | 36 | 1. Fork 本仓库 37 | 2. 新建 Feat_xxx 分支 38 | 3. 提交代码 39 | 4. 新建 Pull Request 40 | 41 | 42 | #### 特技 43 | 44 | 1. 使用 Readme\_XXX.md 来支持不同的语言,例如 Readme\_en.md, Readme\_zh.md 45 | 2. Github 官方博客 [github.com](https://github.com/makermare) 46 | 3. 你可以 [https://gitee.com/makermare](https://gitee.com/makermare) 这个地址来了解 Gitee 上的优秀开源项目 47 | 4. [GVP](https://gitee.com/makermare) 全称是 Gitee 最有价值开源项目,是综合评定出的优秀开源项目 48 | -------------------------------------------------------------------------------- /飞控任务和控制任务流程图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/makermare/UAV-FlyingControlSystem-BlueSkyFlightControl/d35d104cc8a21090000b984fbafd00f08f8a0f3e/飞控任务和控制任务流程图.png -------------------------------------------------------------------------------- /飞行任务状态图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/makermare/UAV-FlyingControlSystem-BlueSkyFlightControl/d35d104cc8a21090000b984fbafd00f08f8a0f3e/飞行任务状态图.png -------------------------------------------------------------------------------- /飞行状态更新(原天穹代码).png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/makermare/UAV-FlyingControlSystem-BlueSkyFlightControl/d35d104cc8a21090000b984fbafd00f08f8a0f3e/飞行状态更新(原天穹代码).png --------------------------------------------------------------------------------