├── .gitignore
├── CAUC-Flight.uvguix.zhang
├── CAUC-Flight.uvoptx
├── CAUC-Flight.uvprojx
├── CAUC-Flight
├── Libraries
│ ├── inc
│ │ ├── arm_common_tables.h
│ │ ├── arm_const_structs.h
│ │ ├── arm_math.h
│ │ ├── cmsis_os.h
│ │ ├── core_cm4.h
│ │ ├── core_cm4_simd.h
│ │ ├── core_cmFunc.h
│ │ ├── core_cmInstr.h
│ │ ├── integer.h
│ │ ├── main.h
│ │ ├── misc.h
│ │ ├── stm32f4xx_adc.h
│ │ ├── stm32f4xx_can.h
│ │ ├── stm32f4xx_conf.h
│ │ ├── stm32f4xx_crc.h
│ │ ├── stm32f4xx_cryp.h
│ │ ├── stm32f4xx_dac.h
│ │ ├── stm32f4xx_dbgmcu.h
│ │ ├── stm32f4xx_dcmi.h
│ │ ├── stm32f4xx_dma.h
│ │ ├── stm32f4xx_dma2d.h
│ │ ├── stm32f4xx_exti.h
│ │ ├── stm32f4xx_flash.h
│ │ ├── stm32f4xx_fmc.h
│ │ ├── stm32f4xx_fsmc.h
│ │ ├── stm32f4xx_gpio.h
│ │ ├── stm32f4xx_hash.h
│ │ ├── stm32f4xx_i2c.h
│ │ ├── stm32f4xx_iwdg.h
│ │ ├── stm32f4xx_ltdc.h
│ │ ├── stm32f4xx_pwr.h
│ │ ├── stm32f4xx_rcc.h
│ │ ├── stm32f4xx_rng.h
│ │ ├── stm32f4xx_rtc.h
│ │ ├── stm32f4xx_sai.h
│ │ ├── stm32f4xx_sdio.h
│ │ ├── stm32f4xx_spi.h
│ │ ├── stm32f4xx_syscfg.h
│ │ ├── stm32f4xx_tim.h
│ │ ├── stm32f4xx_usart.h
│ │ ├── stm32f4xx_wwdg.h
│ │ └── system_stm32f4xx.h
│ └── src
│ │ ├── misc.c
│ │ ├── stm32f4xx_adc.c
│ │ ├── stm32f4xx_can.c
│ │ ├── stm32f4xx_crc.c
│ │ ├── stm32f4xx_cryp.c
│ │ ├── stm32f4xx_cryp_aes.c
│ │ ├── stm32f4xx_cryp_des.c
│ │ ├── stm32f4xx_cryp_tdes.c
│ │ ├── stm32f4xx_dac.c
│ │ ├── stm32f4xx_dbgmcu.c
│ │ ├── stm32f4xx_dcmi.c
│ │ ├── stm32f4xx_dma.c
│ │ ├── stm32f4xx_dma2d.c
│ │ ├── stm32f4xx_exti.c
│ │ ├── stm32f4xx_flash.c
│ │ ├── stm32f4xx_fmc.c
│ │ ├── stm32f4xx_fsmc.c
│ │ ├── stm32f4xx_gpio.c
│ │ ├── stm32f4xx_hash.c
│ │ ├── stm32f4xx_hash_md5.c
│ │ ├── stm32f4xx_hash_sha1.c
│ │ ├── stm32f4xx_i2c.c
│ │ ├── stm32f4xx_iwdg.c
│ │ ├── stm32f4xx_ltdc.c
│ │ ├── stm32f4xx_pwr.c
│ │ ├── stm32f4xx_rcc.c
│ │ ├── stm32f4xx_rng.c
│ │ ├── stm32f4xx_rtc.c
│ │ ├── stm32f4xx_sai.c
│ │ ├── stm32f4xx_sdio.c
│ │ ├── stm32f4xx_spi.c
│ │ ├── stm32f4xx_syscfg.c
│ │ ├── stm32f4xx_tim.c
│ │ ├── stm32f4xx_usart.c
│ │ └── stm32f4xx_wwdg.c
├── applications
│ ├── OFposition_control.c
│ ├── OFposition_control.h
│ ├── Optical_Flow.c
│ ├── Optical_Flow.h
│ ├── PIX_Optical_Flow.c
│ ├── PIX_Optical_Flow.h
│ ├── ctrl.c
│ ├── ctrl.h
│ ├── data_transfer.c
│ ├── data_transfer.h
│ ├── filter.c
│ ├── filter.h
│ ├── height_ctrl.c
│ ├── height_ctrl.h
│ ├── imu.c
│ ├── imu.h
│ ├── init.c
│ ├── init.h
│ ├── main.c
│ ├── mymath.c
│ ├── mymath.h
│ ├── position_control.c
│ ├── position_control.h
│ ├── rc.c
│ ├── rc.h
│ ├── scheduler.c
│ ├── scheduler.h
│ ├── time.c
│ └── time.h
├── devices
│ ├── device_ak8975.c
│ ├── device_ak8975.h
│ ├── device_beep.c
│ ├── device_beep.h
│ ├── device_fatfs.c
│ ├── device_fatfs.h
│ ├── device_fatfs_conf.h
│ ├── device_iic.c
│ ├── device_iic.h
│ ├── device_led.c
│ ├── device_led.h
│ ├── device_mpu6050.c
│ ├── device_mpu6050.h
│ ├── device_ms5611.c
│ ├── device_ms5611.h
│ ├── device_power.c
│ ├── device_power.h
│ ├── device_pwm_in.c
│ ├── device_pwm_in.h
│ ├── device_pwm_out.c
│ ├── device_pwm_out.h
│ ├── device_timer.c
│ ├── device_timer.h
│ ├── device_usart.c
│ ├── device_usart.h
│ ├── device_w25qxx.c
│ ├── device_w25qxx.h
│ ├── integer.h
│ ├── usb_config.c
│ ├── usbd_STM32F4xx_FS.c
│ ├── usbd_user_hid.c
│ ├── usbd_user_hid.h
│ └── usbd_user_msc.c
└── drivers
│ ├── database.h
│ ├── driver_GPS.c
│ ├── driver_GPS.h
│ ├── driver_ak8975.c
│ ├── driver_ak8975.h
│ ├── driver_beep.c
│ ├── driver_beep.h
│ ├── driver_disk.c
│ ├── driver_disk.h
│ ├── driver_led.c
│ ├── driver_led.h
│ ├── driver_lidarlite.c
│ ├── driver_lidarlite.h
│ ├── driver_mpu6050.c
│ ├── driver_mpu6050.h
│ ├── driver_ms5611.c
│ ├── driver_ms5611.h
│ ├── driver_parameter.c
│ ├── driver_parameter.h
│ ├── driver_power.c
│ ├── driver_power.h
│ ├── driver_pwm_in.c
│ ├── driver_pwm_in.h
│ ├── driver_pwm_out.c
│ ├── driver_pwm_out.h
│ ├── driver_ultrasonic.c
│ ├── driver_ultrasonic.h
│ ├── driver_usart.c
│ └── driver_usart.h
├── CMSIS
├── arm_cortexM4lf_math.lib
├── version.c
└── version.h
├── CORE
├── core_cm4.h
├── core_cm4_simd.h
├── core_cmFunc.h
├── core_cmInstr.h
└── startup_stm32f40_41xxx.s
├── DebugConfig
├── APP_STM32F407VGTx.dbgconf
├── CAUC-Flight_STM32F407VGTx.dbgconf
├── Target_1_STM32F407VGTx.dbgconf
└── applications_STM32F407VGTx.dbgconf
├── JLinkLog.txt
├── JLinkSettings.ini
├── Listings
└── startup_stm32f40_41xxx.lst
├── Objects
├── CAUC-Flight.build_log.htm
├── CAUC-Flight.htm
├── CAUC-Flight.lnp
├── CAUC-Flight.sct
└── CAUC-Flight_CAUC-Flight.dep
├── README.md
├── STM32F40X
├── stm32f4xx.h
├── stm32f4xx_conf.h
├── stm32f4xx_it.c
├── stm32f4xx_it.h
├── system_stm32f4xx.c
└── system_stm32f4xx.h
├── USBStack
├── INC
│ ├── RTL.h
│ ├── rl_usb.h
│ ├── usb.h
│ ├── usb_cdc.h
│ ├── usb_def.h
│ ├── usb_for_lib.h
│ ├── usb_hid.h
│ ├── usb_lib.c
│ ├── usb_lib.h
│ ├── usb_msc.h
│ ├── usbd_cdc.h
│ ├── usbd_cdc_acm.h
│ ├── usbd_core.h
│ ├── usbd_core_cdc.h
│ ├── usbd_core_hid.h
│ ├── usbd_core_msc.h
│ ├── usbd_desc.h
│ ├── usbd_event.h
│ ├── usbd_hid.h
│ ├── usbd_hw.h
│ ├── usbd_lib_cdc.h
│ ├── usbd_lib_hid.h
│ ├── usbd_lib_msc.h
│ └── usbd_msc.h
└── SRC
│ ├── usbd_cdc_acm.c
│ ├── usbd_core.c
│ ├── usbd_core_cdc.c
│ ├── usbd_core_hid.c
│ ├── usbd_core_msc.c
│ ├── usbd_hid.c
│ └── usbd_msc.c
├── 内环PID调试日志.txt
├── 当前程序状态描述.txt
├── 程序调试日志.txt
├── 软件版权声明.txt
└── 遥控控制位置控制模式.txt
/.gitignore:
--------------------------------------------------------------------------------
1 | # Prerequisites
2 | *.d
3 | *.TanZheng
4 |
5 | # Object files
6 | *.o
7 | *.ko
8 | *.obj
9 | *.elf
10 |
11 | # Linker output
12 | *.ilk
13 | *.map
14 | *.exp
15 |
16 | # Precompiled Headers
17 | *.gch
18 | *.pch
19 |
20 | # Libraries
21 | #*.lib
22 | *.a
23 | *.la
24 | *.lo
25 |
26 | # Shared objects (inc. Windows DLLs)
27 | *.dll
28 | *.so
29 | *.so.*
30 | *.dylib
31 |
32 | # Executables
33 | *.exe
34 | *.out
35 | *.app
36 | *.i*86
37 | *.x86_64
38 | *.hex
39 | *.axf
40 | *.crf
41 |
42 | # Debug files
43 | *.dSYM/
44 | *.su
45 | *.idb
46 | *.pdb
47 |
48 | # Kernel Module Compile Results
49 | *.mod*
50 | *.cmd
51 | .tmp_versions/
52 | modules.order
53 | Module.symvers
54 | Mkfile.old
55 | dkms.conf
56 |
--------------------------------------------------------------------------------
/CAUC-Flight/Libraries/inc/arm_const_structs.h:
--------------------------------------------------------------------------------
1 | /* ----------------------------------------------------------------------
2 | * Copyright (C) 2010-20134 ARM Limited. All rights reserved.
3 | *
4 | * $Date: 12. March 2014
5 | * $Revision: V1.4.3
6 | *
7 | * Project: CMSIS DSP Library
8 | * Title: arm_const_structs.h
9 | *
10 | * Description: This file has constant structs that are initialized for
11 | * user convenience. For example, some can be given as
12 | * arguments to the arm_cfft_f32() function.
13 | *
14 | * Target Processor: Cortex-M4/Cortex-M3
15 | *
16 | * Redistribution and use in source and binary forms, with or without
17 | * modification, are permitted provided that the following conditions
18 | * are met:
19 | * - Redistributions of source code must retain the above copyright
20 | * notice, this list of conditions and the following disclaimer.
21 | * - Redistributions in binary form must reproduce the above copyright
22 | * notice, this list of conditions and the following disclaimer in
23 | * the documentation and/or other materials provided with the
24 | * distribution.
25 | * - Neither the name of ARM LIMITED nor the names of its contributors
26 | * may be used to endorse or promote products derived from this
27 | * software without specific prior written permission.
28 | *
29 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
30 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
32 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
33 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
34 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
35 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
36 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
37 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
38 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
39 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
40 | * POSSIBILITY OF SUCH DAMAGE.
41 | * -------------------------------------------------------------------- */
42 |
43 | #ifndef _ARM_CONST_STRUCTS_H
44 | #define _ARM_CONST_STRUCTS_H
45 |
46 | #include "arm_math.h"
47 | #include "arm_common_tables.h"
48 |
49 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len16;
50 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len32;
51 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len64;
52 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len128;
53 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len256;
54 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len512;
55 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len1024;
56 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len2048;
57 | extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len4096;
58 |
59 | #endif
60 |
--------------------------------------------------------------------------------
/CAUC-Flight/Libraries/inc/integer.h:
--------------------------------------------------------------------------------
1 | /*-------------------------------------------*/
2 | /* Integer type definitions for FatFs module */
3 | /*-------------------------------------------*/
4 | #ifndef _FF_INTEGER
5 | #define _FF_INTEGER
6 |
7 | /* This type MUST be 8 bit */
8 | typedef unsigned char BYTE;
9 |
10 | /* These types MUST be 16 bit */
11 | typedef short SHORT;
12 | typedef unsigned short WORD;
13 | typedef unsigned short WCHAR;
14 |
15 | /* These types MUST be 16 bit or 32 bit */
16 | typedef int INT;
17 | typedef unsigned int UINT;
18 |
19 | /* These types MUST be 32 bit */
20 | typedef long LONG;
21 | typedef unsigned long DWORD;
22 |
23 | #endif
24 |
--------------------------------------------------------------------------------
/CAUC-Flight/Libraries/inc/main.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file main.h
4 | * @author Code::Blocks
5 | ******************************************************************************
6 | */
7 | #ifndef __MAIN_H
8 | #define __MAIN_H
9 |
10 | extern void main(void);
11 |
12 | #endif
13 |
14 |
--------------------------------------------------------------------------------
/CAUC-Flight/Libraries/inc/stm32f4xx_conf.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file Project/STM32F4xx_StdPeriph_Templates/stm32f4xx_conf.h
4 | * @author MCD Application Team
5 | * @version V1.0.0
6 | * @date 30-September-2011
7 | * @brief Library configuration file.
8 | ******************************************************************************
9 | * @attention
10 | *
11 | * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
12 | * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
13 | * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
14 | * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
15 | * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
16 | * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
17 | *
18 | *
© COPYRIGHT 2011 STMicroelectronics
19 | ******************************************************************************
20 | */
21 |
22 | /* Define to prevent recursive inclusion -------------------------------------*/
23 | #ifndef __STM32F4xx_CONF_H
24 | #define __STM32F4xx_CONF_H
25 |
26 | /* Includes ------------------------------------------------------------------*/
27 | /* Uncomment the line below to enable peripheral header file inclusion */
28 | #include "stm32f4xx_adc.h"
29 | #include "stm32f4xx_can.h"
30 | //#include "stm32f4xx_crc.h"
31 | //#include "stm32f4xx_cryp.h"
32 | //#include "stm32f4xx_dac.h"
33 | #include "stm32f4xx_dbgmcu.h"
34 | //#include "stm32f4xx_dcmi.h"
35 | #include "stm32f4xx_dma.h"
36 | #include "stm32f4xx_exti.h"
37 | #include "stm32f4xx_flash.h"
38 | //#include "stm32f4xx_fsmc.h"
39 | //#include "stm32f4xx_hash.h"
40 | #include "stm32f4xx_gpio.h"
41 | //#include "stm32f4xx_i2c.h"
42 | //#include "stm32f4xx_iwdg.h"
43 | #include "stm32f4xx_pwr.h"
44 | #include "stm32f4xx_rcc.h"
45 | //#include "stm32f4xx_rng.h"
46 | #include "stm32f4xx_rtc.h"
47 | #include "stm32f4xx_sdio.h"
48 | #include "stm32f4xx_spi.h"
49 | #include "stm32f4xx_syscfg.h"
50 | #include "stm32f4xx_tim.h"
51 | #include "stm32f4xx_usart.h"
52 | //#include "stm32f4xx_wwdg.h"
53 | #include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
54 |
55 | /* Exported types ------------------------------------------------------------*/
56 | /* Exported constants --------------------------------------------------------*/
57 |
58 | /* If an external clock source is used, then the value of the following define
59 | should be set to the value of the external clock source, else, if no external
60 | clock is used, keep this define commented */
61 | /*#define I2S_EXTERNAL_CLOCK_VAL 12288000 */ /* Value of the external clock in Hz */
62 |
63 |
64 | /* Uncomment the line below to expanse the "assert_param" macro in the
65 | Standard Peripheral Library drivers code */
66 | /* #define USE_FULL_ASSERT 1 */
67 |
68 | /* Exported macro ------------------------------------------------------------*/
69 | #ifdef USE_FULL_ASSERT
70 |
71 | /**
72 | * @brief The assert_param macro is used for function's parameters check.
73 | * @param expr: If expr is false, it calls assert_failed function
74 | * which reports the name of the source file and the source
75 | * line number of the call that failed.
76 | * If expr is true, it returns no value.
77 | * @retval None
78 | */
79 | #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
80 | /* Exported functions ------------------------------------------------------- */
81 | void assert_failed(uint8_t* file, uint32_t line);
82 | #else
83 | #define assert_param(expr) ((void)0)
84 | #endif /* USE_FULL_ASSERT */
85 |
86 | #endif /* __STM32F4xx_CONF_H */
87 |
88 | /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
89 |
--------------------------------------------------------------------------------
/CAUC-Flight/Libraries/inc/stm32f4xx_crc.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f4xx_crc.h
4 | * @author MCD Application Team
5 | * @version V1.3.0
6 | * @date 08-November-2013
7 | * @brief This file contains all the functions prototypes for the CRC firmware
8 | * library.
9 | ******************************************************************************
10 | * @attention
11 | *
12 | * © COPYRIGHT 2013 STMicroelectronics
13 | *
14 | * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
15 | * You may not use this file except in compliance with the License.
16 | * You may obtain a copy of the License at:
17 | *
18 | * http://www.st.com/software_license_agreement_liberty_v2
19 | *
20 | * Unless required by applicable law or agreed to in writing, software
21 | * distributed under the License is distributed on an "AS IS" BASIS,
22 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
23 | * See the License for the specific language governing permissions and
24 | * limitations under the License.
25 | *
26 | ******************************************************************************
27 | */
28 |
29 | /* Define to prevent recursive inclusion -------------------------------------*/
30 | #ifndef __STM32F4xx_CRC_H
31 | #define __STM32F4xx_CRC_H
32 |
33 | #ifdef __cplusplus
34 | extern "C" {
35 | #endif
36 |
37 | /* Includes ------------------------------------------------------------------*/
38 | #include "stm32f4xx.h"
39 |
40 | /** @addtogroup STM32F4xx_StdPeriph_Driver
41 | * @{
42 | */
43 |
44 | /** @addtogroup CRC
45 | * @{
46 | */
47 |
48 | /* Exported types ------------------------------------------------------------*/
49 | /* Exported constants --------------------------------------------------------*/
50 |
51 | /** @defgroup CRC_Exported_Constants
52 | * @{
53 | */
54 |
55 | /**
56 | * @}
57 | */
58 |
59 | /* Exported macro ------------------------------------------------------------*/
60 | /* Exported functions --------------------------------------------------------*/
61 |
62 | void CRC_ResetDR(void);
63 | uint32_t CRC_CalcCRC(uint32_t Data);
64 | uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength);
65 | uint32_t CRC_GetCRC(void);
66 | void CRC_SetIDRegister(uint8_t IDValue);
67 | uint8_t CRC_GetIDRegister(void);
68 |
69 | #ifdef __cplusplus
70 | }
71 | #endif
72 |
73 | #endif /* __STM32F4xx_CRC_H */
74 |
75 | /**
76 | * @}
77 | */
78 |
79 | /**
80 | * @}
81 | */
82 |
83 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
84 |
--------------------------------------------------------------------------------
/CAUC-Flight/Libraries/inc/stm32f4xx_dbgmcu.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f4xx_dbgmcu.h
4 | * @author MCD Application Team
5 | * @version V1.3.0
6 | * @date 08-November-2013
7 | * @brief This file contains all the functions prototypes for the DBGMCU firmware library.
8 | ******************************************************************************
9 | * @attention
10 | *
11 | * © COPYRIGHT 2013 STMicroelectronics
12 | *
13 | * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
14 | * You may not use this file except in compliance with the License.
15 | * You may obtain a copy of the License at:
16 | *
17 | * http://www.st.com/software_license_agreement_liberty_v2
18 | *
19 | * Unless required by applicable law or agreed to in writing, software
20 | * distributed under the License is distributed on an "AS IS" BASIS,
21 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
22 | * See the License for the specific language governing permissions and
23 | * limitations under the License.
24 | *
25 | ******************************************************************************
26 | */
27 |
28 | /* Define to prevent recursive inclusion -------------------------------------*/
29 | #ifndef __STM32F4xx_DBGMCU_H
30 | #define __STM32F4xx_DBGMCU_H
31 |
32 | #ifdef __cplusplus
33 | extern "C" {
34 | #endif
35 |
36 | /* Includes ------------------------------------------------------------------*/
37 | #include "stm32f4xx.h"
38 |
39 | /** @addtogroup STM32F4xx_StdPeriph_Driver
40 | * @{
41 | */
42 |
43 | /** @addtogroup DBGMCU
44 | * @{
45 | */
46 |
47 | /* Exported types ------------------------------------------------------------*/
48 | /* Exported constants --------------------------------------------------------*/
49 |
50 | /** @defgroup DBGMCU_Exported_Constants
51 | * @{
52 | */
53 | #define DBGMCU_SLEEP ((uint32_t)0x00000001)
54 | #define DBGMCU_STOP ((uint32_t)0x00000002)
55 | #define DBGMCU_STANDBY ((uint32_t)0x00000004)
56 | #define IS_DBGMCU_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFFF8) == 0x00) && ((PERIPH) != 0x00))
57 |
58 | #define DBGMCU_TIM2_STOP ((uint32_t)0x00000001)
59 | #define DBGMCU_TIM3_STOP ((uint32_t)0x00000002)
60 | #define DBGMCU_TIM4_STOP ((uint32_t)0x00000004)
61 | #define DBGMCU_TIM5_STOP ((uint32_t)0x00000008)
62 | #define DBGMCU_TIM6_STOP ((uint32_t)0x00000010)
63 | #define DBGMCU_TIM7_STOP ((uint32_t)0x00000020)
64 | #define DBGMCU_TIM12_STOP ((uint32_t)0x00000040)
65 | #define DBGMCU_TIM13_STOP ((uint32_t)0x00000080)
66 | #define DBGMCU_TIM14_STOP ((uint32_t)0x00000100)
67 | #define DBGMCU_RTC_STOP ((uint32_t)0x00000400)
68 | #define DBGMCU_WWDG_STOP ((uint32_t)0x00000800)
69 | #define DBGMCU_IWDG_STOP ((uint32_t)0x00001000)
70 | #define DBGMCU_I2C1_SMBUS_TIMEOUT ((uint32_t)0x00200000)
71 | #define DBGMCU_I2C2_SMBUS_TIMEOUT ((uint32_t)0x00400000)
72 | #define DBGMCU_I2C3_SMBUS_TIMEOUT ((uint32_t)0x00800000)
73 | #define DBGMCU_CAN1_STOP ((uint32_t)0x02000000)
74 | #define DBGMCU_CAN2_STOP ((uint32_t)0x04000000)
75 | #define IS_DBGMCU_APB1PERIPH(PERIPH) ((((PERIPH) & 0xF91FE200) == 0x00) && ((PERIPH) != 0x00))
76 |
77 | #define DBGMCU_TIM1_STOP ((uint32_t)0x00000001)
78 | #define DBGMCU_TIM8_STOP ((uint32_t)0x00000002)
79 | #define DBGMCU_TIM9_STOP ((uint32_t)0x00010000)
80 | #define DBGMCU_TIM10_STOP ((uint32_t)0x00020000)
81 | #define DBGMCU_TIM11_STOP ((uint32_t)0x00040000)
82 | #define IS_DBGMCU_APB2PERIPH(PERIPH) ((((PERIPH) & 0xFFF8FFFC) == 0x00) && ((PERIPH) != 0x00))
83 | /**
84 | * @}
85 | */
86 |
87 | /* Exported macro ------------------------------------------------------------*/
88 | /* Exported functions --------------------------------------------------------*/
89 | uint32_t DBGMCU_GetREVID(void);
90 | uint32_t DBGMCU_GetDEVID(void);
91 | void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState);
92 | void DBGMCU_APB1PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState);
93 | void DBGMCU_APB2PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState);
94 |
95 | #ifdef __cplusplus
96 | }
97 | #endif
98 |
99 | #endif /* __STM32F4xx_DBGMCU_H */
100 |
101 | /**
102 | * @}
103 | */
104 |
105 | /**
106 | * @}
107 | */
108 |
109 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
110 |
--------------------------------------------------------------------------------
/CAUC-Flight/Libraries/inc/stm32f4xx_iwdg.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f4xx_iwdg.h
4 | * @author MCD Application Team
5 | * @version V1.3.0
6 | * @date 08-November-2013
7 | * @brief This file contains all the functions prototypes for the IWDG
8 | * firmware library.
9 | ******************************************************************************
10 | * @attention
11 | *
12 | * © COPYRIGHT 2013 STMicroelectronics
13 | *
14 | * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
15 | * You may not use this file except in compliance with the License.
16 | * You may obtain a copy of the License at:
17 | *
18 | * http://www.st.com/software_license_agreement_liberty_v2
19 | *
20 | * Unless required by applicable law or agreed to in writing, software
21 | * distributed under the License is distributed on an "AS IS" BASIS,
22 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
23 | * See the License for the specific language governing permissions and
24 | * limitations under the License.
25 | *
26 | ******************************************************************************
27 | */
28 |
29 | /* Define to prevent recursive inclusion -------------------------------------*/
30 | #ifndef __STM32F4xx_IWDG_H
31 | #define __STM32F4xx_IWDG_H
32 |
33 | #ifdef __cplusplus
34 | extern "C" {
35 | #endif
36 |
37 | /* Includes ------------------------------------------------------------------*/
38 | #include "stm32f4xx.h"
39 |
40 | /** @addtogroup STM32F4xx_StdPeriph_Driver
41 | * @{
42 | */
43 |
44 | /** @addtogroup IWDG
45 | * @{
46 | */
47 |
48 | /* Exported types ------------------------------------------------------------*/
49 | /* Exported constants --------------------------------------------------------*/
50 |
51 | /** @defgroup IWDG_Exported_Constants
52 | * @{
53 | */
54 |
55 | /** @defgroup IWDG_WriteAccess
56 | * @{
57 | */
58 | #define IWDG_WriteAccess_Enable ((uint16_t)0x5555)
59 | #define IWDG_WriteAccess_Disable ((uint16_t)0x0000)
60 | #define IS_IWDG_WRITE_ACCESS(ACCESS) (((ACCESS) == IWDG_WriteAccess_Enable) || \
61 | ((ACCESS) == IWDG_WriteAccess_Disable))
62 | /**
63 | * @}
64 | */
65 |
66 | /** @defgroup IWDG_prescaler
67 | * @{
68 | */
69 | #define IWDG_Prescaler_4 ((uint8_t)0x00)
70 | #define IWDG_Prescaler_8 ((uint8_t)0x01)
71 | #define IWDG_Prescaler_16 ((uint8_t)0x02)
72 | #define IWDG_Prescaler_32 ((uint8_t)0x03)
73 | #define IWDG_Prescaler_64 ((uint8_t)0x04)
74 | #define IWDG_Prescaler_128 ((uint8_t)0x05)
75 | #define IWDG_Prescaler_256 ((uint8_t)0x06)
76 | #define IS_IWDG_PRESCALER(PRESCALER) (((PRESCALER) == IWDG_Prescaler_4) || \
77 | ((PRESCALER) == IWDG_Prescaler_8) || \
78 | ((PRESCALER) == IWDG_Prescaler_16) || \
79 | ((PRESCALER) == IWDG_Prescaler_32) || \
80 | ((PRESCALER) == IWDG_Prescaler_64) || \
81 | ((PRESCALER) == IWDG_Prescaler_128)|| \
82 | ((PRESCALER) == IWDG_Prescaler_256))
83 | /**
84 | * @}
85 | */
86 |
87 | /** @defgroup IWDG_Flag
88 | * @{
89 | */
90 | #define IWDG_FLAG_PVU ((uint16_t)0x0001)
91 | #define IWDG_FLAG_RVU ((uint16_t)0x0002)
92 | #define IS_IWDG_FLAG(FLAG) (((FLAG) == IWDG_FLAG_PVU) || ((FLAG) == IWDG_FLAG_RVU))
93 | #define IS_IWDG_RELOAD(RELOAD) ((RELOAD) <= 0xFFF)
94 | /**
95 | * @}
96 | */
97 |
98 | /**
99 | * @}
100 | */
101 |
102 | /* Exported macro ------------------------------------------------------------*/
103 | /* Exported functions --------------------------------------------------------*/
104 |
105 | /* Prescaler and Counter configuration functions ******************************/
106 | void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess);
107 | void IWDG_SetPrescaler(uint8_t IWDG_Prescaler);
108 | void IWDG_SetReload(uint16_t Reload);
109 | void IWDG_ReloadCounter(void);
110 |
111 | /* IWDG activation function ***************************************************/
112 | void IWDG_Enable(void);
113 |
114 | /* Flag management function ***************************************************/
115 | FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG);
116 |
117 | #ifdef __cplusplus
118 | }
119 | #endif
120 |
121 | #endif /* __STM32F4xx_IWDG_H */
122 |
123 | /**
124 | * @}
125 | */
126 |
127 | /**
128 | * @}
129 | */
130 |
131 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
132 |
--------------------------------------------------------------------------------
/CAUC-Flight/Libraries/inc/stm32f4xx_rng.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f4xx_rng.h
4 | * @author MCD Application Team
5 | * @version V1.3.0
6 | * @date 08-November-2013
7 | * @brief This file contains all the functions prototypes for the Random
8 | * Number Generator(RNG) firmware library.
9 | ******************************************************************************
10 | * @attention
11 | *
12 | * © COPYRIGHT 2013 STMicroelectronics
13 | *
14 | * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
15 | * You may not use this file except in compliance with the License.
16 | * You may obtain a copy of the License at:
17 | *
18 | * http://www.st.com/software_license_agreement_liberty_v2
19 | *
20 | * Unless required by applicable law or agreed to in writing, software
21 | * distributed under the License is distributed on an "AS IS" BASIS,
22 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
23 | * See the License for the specific language governing permissions and
24 | * limitations under the License.
25 | *
26 | ******************************************************************************
27 | */
28 |
29 | /* Define to prevent recursive inclusion -------------------------------------*/
30 | #ifndef __STM32F4xx_RNG_H
31 | #define __STM32F4xx_RNG_H
32 |
33 | #ifdef __cplusplus
34 | extern "C" {
35 | #endif
36 |
37 | /* Includes ------------------------------------------------------------------*/
38 | #include "stm32f4xx.h"
39 |
40 | /** @addtogroup STM32F4xx_StdPeriph_Driver
41 | * @{
42 | */
43 |
44 | /** @addtogroup RNG
45 | * @{
46 | */
47 |
48 | /* Exported types ------------------------------------------------------------*/
49 | /* Exported constants --------------------------------------------------------*/
50 |
51 | /** @defgroup RNG_Exported_Constants
52 | * @{
53 | */
54 |
55 | /** @defgroup RNG_flags_definition
56 | * @{
57 | */
58 | #define RNG_FLAG_DRDY ((uint8_t)0x0001) /*!< Data ready */
59 | #define RNG_FLAG_CECS ((uint8_t)0x0002) /*!< Clock error current status */
60 | #define RNG_FLAG_SECS ((uint8_t)0x0004) /*!< Seed error current status */
61 |
62 | #define IS_RNG_GET_FLAG(RNG_FLAG) (((RNG_FLAG) == RNG_FLAG_DRDY) || \
63 | ((RNG_FLAG) == RNG_FLAG_CECS) || \
64 | ((RNG_FLAG) == RNG_FLAG_SECS))
65 | #define IS_RNG_CLEAR_FLAG(RNG_FLAG) (((RNG_FLAG) == RNG_FLAG_CECS) || \
66 | ((RNG_FLAG) == RNG_FLAG_SECS))
67 | /**
68 | * @}
69 | */
70 |
71 | /** @defgroup RNG_interrupts_definition
72 | * @{
73 | */
74 | #define RNG_IT_CEI ((uint8_t)0x20) /*!< Clock error interrupt */
75 | #define RNG_IT_SEI ((uint8_t)0x40) /*!< Seed error interrupt */
76 |
77 | #define IS_RNG_IT(IT) ((((IT) & (uint8_t)0x9F) == 0x00) && ((IT) != 0x00))
78 | #define IS_RNG_GET_IT(RNG_IT) (((RNG_IT) == RNG_IT_CEI) || ((RNG_IT) == RNG_IT_SEI))
79 | /**
80 | * @}
81 | */
82 |
83 | /**
84 | * @}
85 | */
86 |
87 | /* Exported macro ------------------------------------------------------------*/
88 | /* Exported functions --------------------------------------------------------*/
89 |
90 | /* Function used to set the RNG configuration to the default reset state *****/
91 | void RNG_DeInit(void);
92 |
93 | /* Configuration function *****************************************************/
94 | void RNG_Cmd(FunctionalState NewState);
95 |
96 | /* Get 32 bit Random number function ******************************************/
97 | uint32_t RNG_GetRandomNumber(void);
98 |
99 | /* Interrupts and flags management functions **********************************/
100 | void RNG_ITConfig(FunctionalState NewState);
101 | FlagStatus RNG_GetFlagStatus(uint8_t RNG_FLAG);
102 | void RNG_ClearFlag(uint8_t RNG_FLAG);
103 | ITStatus RNG_GetITStatus(uint8_t RNG_IT);
104 | void RNG_ClearITPendingBit(uint8_t RNG_IT);
105 |
106 | #ifdef __cplusplus
107 | }
108 | #endif
109 |
110 | #endif /*__STM32F4xx_RNG_H */
111 |
112 | /**
113 | * @}
114 | */
115 |
116 | /**
117 | * @}
118 | */
119 |
120 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
121 |
--------------------------------------------------------------------------------
/CAUC-Flight/Libraries/inc/stm32f4xx_wwdg.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f4xx_wwdg.h
4 | * @author MCD Application Team
5 | * @version V1.3.0
6 | * @date 08-November-2013
7 | * @brief This file contains all the functions prototypes for the WWDG firmware
8 | * library.
9 | ******************************************************************************
10 | * @attention
11 | *
12 | * © COPYRIGHT 2013 STMicroelectronics
13 | *
14 | * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
15 | * You may not use this file except in compliance with the License.
16 | * You may obtain a copy of the License at:
17 | *
18 | * http://www.st.com/software_license_agreement_liberty_v2
19 | *
20 | * Unless required by applicable law or agreed to in writing, software
21 | * distributed under the License is distributed on an "AS IS" BASIS,
22 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
23 | * See the License for the specific language governing permissions and
24 | * limitations under the License.
25 | *
26 | ******************************************************************************
27 | */
28 |
29 | /* Define to prevent recursive inclusion -------------------------------------*/
30 | #ifndef __STM32F4xx_WWDG_H
31 | #define __STM32F4xx_WWDG_H
32 |
33 | #ifdef __cplusplus
34 | extern "C" {
35 | #endif
36 |
37 | /* Includes ------------------------------------------------------------------*/
38 | #include "stm32f4xx.h"
39 |
40 | /** @addtogroup STM32F4xx_StdPeriph_Driver
41 | * @{
42 | */
43 |
44 | /** @addtogroup WWDG
45 | * @{
46 | */
47 |
48 | /* Exported types ------------------------------------------------------------*/
49 | /* Exported constants --------------------------------------------------------*/
50 |
51 | /** @defgroup WWDG_Exported_Constants
52 | * @{
53 | */
54 |
55 | /** @defgroup WWDG_Prescaler
56 | * @{
57 | */
58 |
59 | #define WWDG_Prescaler_1 ((uint32_t)0x00000000)
60 | #define WWDG_Prescaler_2 ((uint32_t)0x00000080)
61 | #define WWDG_Prescaler_4 ((uint32_t)0x00000100)
62 | #define WWDG_Prescaler_8 ((uint32_t)0x00000180)
63 | #define IS_WWDG_PRESCALER(PRESCALER) (((PRESCALER) == WWDG_Prescaler_1) || \
64 | ((PRESCALER) == WWDG_Prescaler_2) || \
65 | ((PRESCALER) == WWDG_Prescaler_4) || \
66 | ((PRESCALER) == WWDG_Prescaler_8))
67 | #define IS_WWDG_WINDOW_VALUE(VALUE) ((VALUE) <= 0x7F)
68 | #define IS_WWDG_COUNTER(COUNTER) (((COUNTER) >= 0x40) && ((COUNTER) <= 0x7F))
69 |
70 | /**
71 | * @}
72 | */
73 |
74 | /**
75 | * @}
76 | */
77 |
78 | /* Exported macro ------------------------------------------------------------*/
79 | /* Exported functions --------------------------------------------------------*/
80 |
81 | /* Function used to set the WWDG configuration to the default reset state ****/
82 | void WWDG_DeInit(void);
83 |
84 | /* Prescaler, Refresh window and Counter configuration functions **************/
85 | void WWDG_SetPrescaler(uint32_t WWDG_Prescaler);
86 | void WWDG_SetWindowValue(uint8_t WindowValue);
87 | void WWDG_EnableIT(void);
88 | void WWDG_SetCounter(uint8_t Counter);
89 |
90 | /* WWDG activation function ***************************************************/
91 | void WWDG_Enable(uint8_t Counter);
92 |
93 | /* Interrupts and flags management functions **********************************/
94 | FlagStatus WWDG_GetFlagStatus(void);
95 | void WWDG_ClearFlag(void);
96 |
97 | #ifdef __cplusplus
98 | }
99 | #endif
100 |
101 | #endif /* __STM32F4xx_WWDG_H */
102 |
103 | /**
104 | * @}
105 | */
106 |
107 | /**
108 | * @}
109 | */
110 |
111 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
112 |
--------------------------------------------------------------------------------
/CAUC-Flight/Libraries/inc/system_stm32f4xx.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file system_stm32f4xx.h
4 | * @author MCD Application Team
5 | * @version V1.3.0
6 | * @date 08-November-2013
7 | * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
8 | ******************************************************************************
9 | * @attention
10 | *
11 | * © COPYRIGHT 2013 STMicroelectronics
12 | *
13 | * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
14 | * You may not use this file except in compliance with the License.
15 | * You may obtain a copy of the License at:
16 | *
17 | * http://www.st.com/software_license_agreement_liberty_v2
18 | *
19 | * Unless required by applicable law or agreed to in writing, software
20 | * distributed under the License is distributed on an "AS IS" BASIS,
21 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
22 | * See the License for the specific language governing permissions and
23 | * limitations under the License.
24 | *
25 | ******************************************************************************
26 | */
27 |
28 | /** @addtogroup CMSIS
29 | * @{
30 | */
31 |
32 | /** @addtogroup stm32f4xx_system
33 | * @{
34 | */
35 |
36 | /**
37 | * @brief Define to prevent recursive inclusion
38 | */
39 | #ifndef __SYSTEM_STM32F4XX_H
40 | #define __SYSTEM_STM32F4XX_H
41 |
42 | #ifdef __cplusplus
43 | extern "C" {
44 | #endif
45 |
46 | /** @addtogroup STM32F4xx_System_Includes
47 | * @{
48 | */
49 |
50 | /**
51 | * @}
52 | */
53 |
54 |
55 | /** @addtogroup STM32F4xx_System_Exported_types
56 | * @{
57 | */
58 |
59 | extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
60 |
61 |
62 | /**
63 | * @}
64 | */
65 |
66 | /** @addtogroup STM32F4xx_System_Exported_Constants
67 | * @{
68 | */
69 |
70 | /**
71 | * @}
72 | */
73 |
74 | /** @addtogroup STM32F4xx_System_Exported_Macros
75 | * @{
76 | */
77 |
78 | /**
79 | * @}
80 | */
81 |
82 | /** @addtogroup STM32F4xx_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_STM32F4XX_H */
97 |
98 | /**
99 | * @}
100 | */
101 |
102 | /**
103 | * @}
104 | */
105 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
106 |
--------------------------------------------------------------------------------
/CAUC-Flight/Libraries/src/stm32f4xx_crc.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f4xx_crc.c
4 | * @author MCD Application Team
5 | * @version V1.3.0
6 | * @date 08-November-2013
7 | * @brief This file provides all the CRC firmware functions.
8 | ******************************************************************************
9 | * @attention
10 | *
11 | * © COPYRIGHT 2013 STMicroelectronics
12 | *
13 | * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
14 | * You may not use this file except in compliance with the License.
15 | * You may obtain a copy of the License at:
16 | *
17 | * http://www.st.com/software_license_agreement_liberty_v2
18 | *
19 | * Unless required by applicable law or agreed to in writing, software
20 | * distributed under the License is distributed on an "AS IS" BASIS,
21 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
22 | * See the License for the specific language governing permissions and
23 | * limitations under the License.
24 | *
25 | ******************************************************************************
26 | */
27 |
28 | /* Includes ------------------------------------------------------------------*/
29 | #include "stm32f4xx_crc.h"
30 |
31 | /** @addtogroup STM32F4xx_StdPeriph_Driver
32 | * @{
33 | */
34 |
35 | /** @defgroup CRC
36 | * @brief CRC driver modules
37 | * @{
38 | */
39 |
40 | /* Private typedef -----------------------------------------------------------*/
41 | /* Private define ------------------------------------------------------------*/
42 | /* Private macro -------------------------------------------------------------*/
43 | /* Private variables ---------------------------------------------------------*/
44 | /* Private function prototypes -----------------------------------------------*/
45 | /* Private functions ---------------------------------------------------------*/
46 |
47 | /** @defgroup CRC_Private_Functions
48 | * @{
49 | */
50 |
51 | /**
52 | * @brief Resets the CRC Data register (DR).
53 | * @param None
54 | * @retval None
55 | */
56 | void CRC_ResetDR(void)
57 | {
58 | /* Reset CRC generator */
59 | CRC->CR = CRC_CR_RESET;
60 | }
61 |
62 | /**
63 | * @brief Computes the 32-bit CRC of a given data word(32-bit).
64 | * @param Data: data word(32-bit) to compute its CRC
65 | * @retval 32-bit CRC
66 | */
67 | uint32_t CRC_CalcCRC(uint32_t Data)
68 | {
69 | CRC->DR = Data;
70 |
71 | return (CRC->DR);
72 | }
73 |
74 | /**
75 | * @brief Computes the 32-bit CRC of a given buffer of data word(32-bit).
76 | * @param pBuffer: pointer to the buffer containing the data to be computed
77 | * @param BufferLength: length of the buffer to be computed
78 | * @retval 32-bit CRC
79 | */
80 | uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength)
81 | {
82 | uint32_t index = 0;
83 |
84 | for(index = 0; index < BufferLength; index++)
85 | {
86 | CRC->DR = pBuffer[index];
87 | }
88 | return (CRC->DR);
89 | }
90 |
91 | /**
92 | * @brief Returns the current CRC value.
93 | * @param None
94 | * @retval 32-bit CRC
95 | */
96 | uint32_t CRC_GetCRC(void)
97 | {
98 | return (CRC->DR);
99 | }
100 |
101 | /**
102 | * @brief Stores a 8-bit data in the Independent Data(ID) register.
103 | * @param IDValue: 8-bit value to be stored in the ID register
104 | * @retval None
105 | */
106 | void CRC_SetIDRegister(uint8_t IDValue)
107 | {
108 | CRC->IDR = IDValue;
109 | }
110 |
111 | /**
112 | * @brief Returns the 8-bit data stored in the Independent Data(ID) register
113 | * @param None
114 | * @retval 8-bit value of the ID register
115 | */
116 | uint8_t CRC_GetIDRegister(void)
117 | {
118 | return (CRC->IDR);
119 | }
120 |
121 | /**
122 | * @}
123 | */
124 |
125 | /**
126 | * @}
127 | */
128 |
129 | /**
130 | * @}
131 | */
132 |
133 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
134 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/OFposition_control.c:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file OFposition_control.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 光流控制文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #include "OFposition_control.h"
16 | #include "Optical_Flow.h"
17 | #include "mymath.h"
18 | #include "rc.h"
19 | #include "database.h"
20 | #include "driver_parameter.h"
21 | #include "driver_ultrasonic.h"
22 |
23 | /* 光流定点最大速度控制 单位 mm/s */
24 | #define Max_OF_SPEED 1000.0f
25 |
26 | /* 期望的row速度和yaw速度*/
27 | float exp_row_speed = 0;
28 | float exp_yaw_speed = 0;
29 | /* 期望的row速度和yaw速度偏差*/
30 | float exp_row_speed_err , exp_yaw_speed_err;
31 | /* 期望的row速度和yaw速度上一次偏差*/
32 | float exp_row_speed_err_old , exp_yaw_speed_err_old;
33 | /* 期望速度的比例 */
34 | float expect_speed_row_P , expect_speed_yaw_P;
35 | /* 期望速度的积分 */
36 | float expect_speed_row_I , expect_speed_yaw_I;
37 | /* 期望速度的微分 */
38 | float expect_speed_row_D , expect_speed_yaw_D;
39 | /* PID计算的角度值单位0.1mm/s */
40 | float expect_of_pitch,expect_of_roll;
41 | /* 实际输出的角度值 */
42 | float expect_of_pitch_out,expect_of_roll_out;
43 |
44 |
45 | /*----------------------------------------------------------
46 | + 实现功能:串级位置PID控制悬停
47 | + 调用参数:两次调用时间间隔
48 | ----------------------------------------------------------*/
49 | void OF_PositionControl_Mode(float Timer_t)
50 | {
51 |
52 | }
53 |
54 | /*----------------------------------------------------------
55 | + 实现功能:速度PID控制悬停
56 | + 调用参数:两次调用时间间隔
57 | ----------------------------------------------------------*/
58 | void OF_SpeedControl_Mode(float Timer_t)
59 | {
60 | /* 当超声波高度大于200mm开始光流定点(当前处于调试阶段,后期会和GPS融合) */
61 | if(ultra_distance > 200)
62 | {
63 | /* 光流期望X速度 */
64 | exp_row_speed = Max_OF_SPEED *( my_deathzoom( ( CH_filter[ROL]) ,30 )/500.0f ) ;
65 | /* 光流期望Y速度 */
66 | exp_yaw_speed = Max_OF_SPEED *( my_deathzoom( (-CH_filter[PIT]) ,30 )/500.0f );
67 | /* 光流期望X速度偏差 */
68 | exp_row_speed_err = exp_row_speed - Flow_Comp_x;
69 | /* 光流期望Y速度偏差 */
70 | exp_yaw_speed_err = exp_yaw_speed + Flow_Comp_y;
71 |
72 |
73 | /* 光流速度偏移量 的比例 */
74 | expect_speed_row_P=pid_setup.groups.ctrl6.kp *exp_row_speed_err;
75 | expect_speed_yaw_P=pid_setup.groups.ctrl6.kp *exp_yaw_speed_err;
76 |
77 | /* 光流速度偏移量 的积分 */
78 | expect_speed_row_I+=pid_setup.groups.ctrl6.ki *exp_row_speed_err;
79 | expect_speed_yaw_I+=pid_setup.groups.ctrl6.ki *exp_yaw_speed_err;
80 |
81 | /* 光流速度偏移量 的微分 */
82 | expect_speed_row_D=pid_setup.groups.ctrl6.kd *(exp_row_speed_err-exp_row_speed_err_old);
83 | expect_speed_yaw_D=pid_setup.groups.ctrl6.kd *(exp_yaw_speed_err-exp_yaw_speed_err_old);
84 | /* 保存光流速度偏移量 的微分 */
85 | exp_row_speed_err_old=exp_row_speed_err;
86 | exp_yaw_speed_err_old=exp_yaw_speed_err;
87 |
88 | /* 低油门时 */
89 | if(CH_filter[THR]<-400)
90 | {
91 | expect_speed_row_I=0;//积分清零
92 | expect_speed_yaw_I=0;//积分清零
93 | expect_of_roll_out = 0;//光流计算的角度偏移清零
94 | expect_of_pitch = 0;
95 | expect_of_roll_out = 0;//光流计算的输出角度偏移清零
96 | expect_of_pitch_out = 0;
97 | }
98 | expect_speed_row_I = LIMIT(expect_speed_row_I,-300,300);
99 | expect_speed_yaw_I = LIMIT(expect_speed_yaw_I,-300,300);
100 |
101 | /* 期望速度的PID输出 */
102 | expect_of_roll=LIMIT(expect_speed_row_P+expect_speed_row_I+expect_speed_row_D,-600,600);
103 | expect_of_pitch=LIMIT(expect_speed_yaw_P+expect_speed_yaw_I+expect_speed_yaw_D,-600,600);
104 |
105 | expect_of_roll_out = expect_of_roll * 0.01f;
106 | expect_of_pitch_out = expect_of_pitch * 0.01f;
107 | }
108 | else
109 | {
110 | expect_speed_row_I=0;//积分清零
111 | expect_speed_yaw_I=0;//积分清零
112 |
113 | expect_of_roll_out = 0;//光流计算的补偿角清零
114 | expect_of_pitch = 0;
115 | expect_of_roll_out = 0;//光流计算的输出补偿角清零
116 | expect_of_pitch_out = 0;
117 | }
118 |
119 | }
120 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/OFposition_control.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 光流控制头文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef __OFPOSITION_CONTROL_H__
16 | #define __OFPOSITION_CONTROL_H__
17 |
18 | #include "stm32f4xx.h"
19 |
20 | /* 实际输出的角度值 */
21 | extern float expect_of_pitch_out,expect_of_roll_out;
22 | /* 光流定点的速度环输出 */
23 | void OF_SpeedControl_Mode(float Timer_t);
24 |
25 |
26 | #endif
27 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/Optical_Flow.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file Optical_Flow.h
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 光流驱动头文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _OPTICAL_FLOW_H
16 | #define _OPTICAL_FLOW_H
17 |
18 | #include "stm32f4xx.h"
19 |
20 | /* 读取X偏移量原始数据 */
21 | extern int Optical_flow_org_x;
22 | /* 读取Y偏移量原始数据 */
23 | extern int Optical_flow_org_y;
24 | /* 读取Confidence原始数据 */
25 | extern int Optical_flow_confidence;
26 |
27 | /* 换算到X像素速度 光流像素要结合高度才能算出速度 值范围约+-200.000 */
28 | extern float Optical_flow_x;
29 | /* 换算到Y像素速度 光流像素要结合高度才能算出速度 值范围约+-200.000 */
30 | extern float Optical_flow_y;
31 | /* 读取画面不变率 值范围0-100 */
32 | extern float Optical_flow_con;
33 |
34 | /* 光流通过陀螺和超声波补偿后的速度 */
35 | extern float Flow_Comp_x,Flow_Comp_y;
36 | /* 光流通过超声波补偿后的速度 */
37 | extern float no_compen_x_speed,no_compen_y_speed;
38 | /* 光流积分位移 */
39 | extern float OF_Offset_x,OF_Offset_y;
40 |
41 | /*----------------------------------------------------------
42 | + 实现功能:数据接收并保存
43 | + 调用参数:接收到的单字节数据
44 | ----------------------------------------------------------*/
45 | extern void Optical_Flow_Receive_Prepare(u8 data);
46 |
47 | /*----------------------------------------------------------
48 | + 实现功能:光流初始化
49 | ----------------------------------------------------------*/
50 | extern void Optical_Flow_init(void);
51 |
52 | #endif
53 |
54 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/PIX_Optical_Flow.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 光流驱动头文件
7 | *@design 无人机研究小组
8 | 谭政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _OPTICAL_FLOW_H
16 | #define _OPTICAL_FLOW_H
17 |
18 | #include "stm32f4xx.h"
19 |
20 | /*下面开始加入PIX光流读取代码 add by zhangshuo*/
21 | typedef struct
22 | {
23 | float average;//Flow in m in x-sensor direction, angular-speed compensated
24 | float originf;
25 | int16_t origin;
26 | }FLOW_DATA;
27 |
28 | typedef struct
29 | {
30 | uint64_t time_sec;
31 | u8 id;
32 | FLOW_DATA flow_x;
33 | FLOW_DATA flow_y;
34 | FLOW_DATA flow_comp_x;//Flow in m in x-sensor direction, angular-speed compensated
35 | FLOW_DATA flow_comp_y;
36 | u8 quality; //Optical flow quality / confidence. 0: bad, 255: maximum quality
37 | FLOW_DATA hight;//ground_distance float Ground distance in m. Positive value: distance known. Negative value: Unknown distance
38 | }FLOW;
39 |
40 | typedef struct
41 | {
42 | uint64_t time_usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot)
43 | uint32_t integration_time_us; ///< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
44 | float integrated_x; ///< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
45 | float integrated_y; ///< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
46 | float integrated_xgyro; ///< RH rotation around X axis (rad)
47 | float integrated_ygyro; ///< RH rotation around Y axis (rad)
48 | float integrated_zgyro; ///< RH rotation around Z axis (rad)
49 | uint32_t time_delta_distance_us; ///< Time in microseconds since the distance was sampled.
50 | float distance; ///< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
51 | int16_t temperature; ///< Temperature * 100 in centi-degrees Celsius
52 | uint8_t sensor_id; ///< Sensor ID
53 | uint8_t quality; ///< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
54 | }FLOW_RAD;
55 |
56 | typedef struct
57 | {
58 | FLOW_DATA flow_x;
59 | FLOW_DATA flow_y;
60 | FLOW_DATA flow_comp_x;//Flow in m in x-sensor direction, angular-speed compensated
61 | FLOW_DATA flow_comp_y;
62 | float scale_rad_fix;
63 | float scale_rad_fix_comp;
64 | FLOW_DATA hight;//ground_distance float Ground distance in m. Positive value: distance known. Negative value: Unknown distance
65 | }FLOW_FIX;
66 |
67 |
68 |
69 |
70 |
71 |
72 | /* 读取X偏移量原始数据 */
73 | extern int Optical_flow_org_x;
74 | /* 读取Y偏移量原始数据 */
75 | extern int Optical_flow_org_y;
76 | /* 读取Confidence原始数据 */
77 | extern int Optical_flow_confidence;
78 |
79 | /* 换算到X像素速度 光流像素要结合高度才能算出速度 值范围约+-200.000 */
80 | extern float Optical_flow_x;
81 | /* 换算到Y像素速度 光流像素要结合高度才能算出速度 值范围约+-200.000 */
82 | extern float Optical_flow_y;
83 | /* 读取画面不变率 值范围0-100 */
84 | extern float Optical_flow_con;
85 |
86 | /*----------------------------------------------------------
87 | + 实现功能:数据接收并保存
88 | + 调用参数:接收到的单字节数据
89 | ----------------------------------------------------------*/
90 | extern void Optical_Flow_Receive_Prepare(u8 data);
91 |
92 | /*----------------------------------------------------------
93 | + 实现功能:光流初始化
94 | ----------------------------------------------------------*/
95 | extern void Optical_Flow_init(void);
96 |
97 | #endif
98 |
99 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/ctrl.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 飞控控制头文件
7 | *@design 无人机研究小组
8 | 谭政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _CTRL_H
16 | #define _CTRL_H
17 |
18 | #include "stm32f4xx.h"
19 | #include "driver_pwm_out.h"
20 | #include "rc.h"
21 | #include "imu.h"
22 | #include "driver_mpu6050.h"
23 |
24 | /* PID控制轴枚举体 */
25 | enum
26 | {
27 | PIDROLL,
28 | PIDPITCH,
29 | PIDYAW,
30 | PID4,
31 | PID5,
32 | PID6,
33 | PIDITEMS
34 | };
35 |
36 | /* PID控制结构体 */
37 | typedef struct
38 | {
39 | xyz_f_t err;
40 | xyz_f_t err_old;
41 | xyz_f_t err_i;
42 | xyz_f_t eliminate_I;
43 | xyz_f_t err_d;
44 | xyz_f_t damp;
45 | xyz_f_t out;
46 | pid_t PID[PIDITEMS];
47 | xyz_f_t err_weight;
48 | float FB;
49 | } ctrl_t;
50 |
51 | /* 机架类型 */
52 | extern char OP_COPTER ;
53 | /* 角速度控制结构体 */
54 | extern ctrl_t ctrl_angular_velocity;
55 | /* 姿态控制结构体 */
56 | extern ctrl_t ctrl_attitude;
57 | /* 低油门信号判断 */
58 | extern u8 Thr_Low;
59 | /* 滤波后油门数据 */
60 | extern float Thr_Weight;
61 | /* 单个电机的总控制量 */
62 | extern float motor[8];
63 |
64 | /*----------------------------------------------------------
65 | + 实现功能:恢复默认控制幅度
66 | ----------------------------------------------------------*/
67 | extern void Ctrl_Para_Init(void);
68 |
69 | /*----------------------------------------------------------
70 | + 实现功能:姿态PID控制角速度 由任务调度调用周期5ms
71 | + 调用参数:两次调用间隔
72 | ----------------------------------------------------------*/
73 | extern void CTRL_attitude(float);
74 |
75 | /*----------------------------------------------------------
76 | + 实现功能:角速度电机输出量 由任务调度调用周期2ms
77 | + 调用参数:两次调用间隔
78 | ----------------------------------------------------------*/
79 | extern void CTRL_angular_velocity(float);
80 |
81 | #endif
82 |
83 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/data_transfer.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 数据传输头文件
7 | *@design 无人机研究小组
8 | 谭政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _DATA_TRANSFER_H
16 | #define _DATA_TRANSFER_H
17 |
18 | #include "stm32f4xx.h"
19 | #include "height_ctrl.h"
20 |
21 | //#define DT_USE_USART2 //开启串口2数传功能
22 | #define DT_USE_USB_HID //开启飞控USBHID连接上位机功能
23 | #define DT_USE_ATO_SP //使用匿名发送速度
24 | //#define DT_USE_LIT_SP //使用light发送速度
25 |
26 | /* 等待发送数据的标志 */
27 | extern u8 wait_for_translate;
28 | /* 等待发送数据的标志结构体 */
29 | typedef struct
30 | {
31 | u8 send_status;
32 | u8 send_speed;
33 | u8 send_rcdata;
34 | u8 send_motopwm;
35 | u8 send_senser;
36 | u8 send_senser2;
37 | u8 send_location;
38 | u8 send_power;
39 | u8 send_pid1;
40 | u8 send_pid2;
41 | u8 send_pid3;
42 | u8 send_pid4;
43 | u8 send_user;
44 | } dt_flag_t;
45 |
46 | /*----------------------------------------------------------
47 | + 实现功能:由任务调度调用周期1ms
48 | ----------------------------------------------------------*/
49 | extern void Call_Data_transfer(void);
50 |
51 | /*----------------------------------------------------------
52 | + 实现功能:数传初始化
53 | ----------------------------------------------------------*/
54 | extern void Data_transfer_init(void);
55 |
56 | /*----------------------------------------------------------
57 | + 实现功能:数据接收并保存
58 | + 调用参数:接收到的单字节数据
59 | ----------------------------------------------------------*/
60 | extern void DT_Data_Receive_Prepare(u8 data);
61 |
62 | #endif
63 |
64 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/filter.c:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file filter.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 数据滤波文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #include "stm32f4xx.h"
16 | #include "filter.h"
17 | #include "mymath.h"
18 |
19 | /* 计算求取中位数组总数 */
20 | #define MED_WIDTH_NUM 11
21 | /* 计算求取浮点中位数组项 */
22 | #define MED_FIL_ITEM 2
23 | /* 计算求取整形中位数组项 */
24 | #define MED_FIL_ITEM_int 2
25 |
26 | /* 计算求取浮点中位数组 */
27 | float med_filter_tmp[MED_FIL_ITEM][MED_WIDTH_NUM ];
28 | /* 计算求取整形中位数组 */
29 | int med_filter_tmp_int[MED_FIL_ITEM_int][MED_WIDTH_NUM ];
30 | /* 计算求取整形中位数组下标 */
31 | u8 med_fil_cnt[MED_FIL_ITEM];
32 |
33 | /*----------------------------------------------------------
34 | + 实现功能:float类型数据滑动窗口滤波
35 | + 调用参数:in:加入的数据 moavarray[]:滑动窗口数组 len:求取数据个数 fil_cnt[2]:数组下标
36 | + 调用参数:*out :算出的中位数
37 | ----------------------------------------------------------*/
38 | void Moving_Average(float in,float moavarray[],u16 len ,u16 fil_cnt[2],float *out)
39 | {
40 | u16 width_num = len ;
41 | if( ++fil_cnt[0] > width_num )
42 | {
43 | fil_cnt[0] = 0; //now
44 | fil_cnt[1] = 1; //old
45 | }
46 | else
47 | fil_cnt[1] = (fil_cnt[0] == width_num)? 0 : (fil_cnt[0] + 1);
48 | moavarray[ fil_cnt[0] ] = in;
49 | *out += ( in - ( moavarray[ fil_cnt[1] ] ) )/(float)( width_num ) ;
50 | }
51 |
52 | /*----------------------------------------------------------
53 | + 实现功能:float类型数据求中位数
54 | + 调用参数:item:项目 width_num:求取数据个数 in:加入的数据
55 | + 返回参数:算出的中位数
56 | ----------------------------------------------------------*/
57 | float Moving_Median(u8 item,u8 width_num,float in)
58 | {
59 | u8 i,j;
60 | float t;
61 | float tmp[MED_WIDTH_NUM];
62 |
63 | if(item >= MED_FIL_ITEM || width_num >= MED_WIDTH_NUM )
64 | return 0;
65 | else
66 | {
67 | if( ++med_fil_cnt[item] >= width_num )
68 | med_fil_cnt[item] = 0;
69 | med_filter_tmp[item][ med_fil_cnt[item] ] = in;
70 | for(i=0; i tmp[j+1])
77 | {
78 | t = tmp[j];
79 | tmp[j] = tmp[j+1];
80 | tmp[j+1] = t;
81 | }
82 | }
83 | }
84 | return ( tmp[(u16)width_num/2] );
85 | }
86 | }
87 |
88 | /*----------------------------------------------------------
89 | + 实现功能:int类型数据求中位数
90 | + 调用参数:item:项目 width_num:求取数据个数 in:加入的数据
91 | + 返回参数:算出的中位数
92 | ----------------------------------------------------------*/
93 | int Moving_Median_int(u8 item,u8 width_num,int in_int)
94 | {
95 | u8 i,j;
96 | int t_int;
97 | int tmp[MED_WIDTH_NUM];
98 |
99 | if(item >= MED_FIL_ITEM || width_num >= MED_WIDTH_NUM )
100 | return 0;
101 | else
102 | {
103 | if( ++med_fil_cnt[item] >= width_num )
104 | med_fil_cnt[item] = 0;
105 | med_filter_tmp_int[item][ med_fil_cnt[item] ] = in_int;
106 | for(i=0; i tmp[j+1])
113 | {
114 | t_int = tmp[j];
115 | tmp[j] = tmp[j+1];
116 | tmp[j+1] = t_int;
117 | }
118 | }
119 | }
120 | return ( tmp[(u16)width_num/2] );
121 | }
122 | }
123 |
124 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/filter.h:
--------------------------------------------------------------------------------
1 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved.
2 | + 文件名 :filter.h
3 | + 描述 :数据滤波头文件
4 | 代码尽量做到逐行注释 代码有问题,及时加群交流 作者有偿支持对开源代码的完善 */
5 | #ifndef __FILTER_H
6 | #define __FILTER_H
7 |
8 | #include "driver_parameter.h"
9 |
10 | /*----------------------------------------------------------
11 | + 实现功能:float类型数据滑动窗口滤波
12 | + 调用参数:in:加入的数据 moavarray[]:滑动窗口数组 len:求取数据个数 fil_cnt[2]:数组下标
13 | + 调用参数:*out :算出的中位数
14 | ----------------------------------------------------------*/
15 | extern void Moving_Average(float in,float moavarray[],u16 len ,u16 fil_cnt[2],float *out);
16 |
17 | /*----------------------------------------------------------
18 | + 实现功能:float类型数据求中位数
19 | + 调用参数:item:项目 width_num:求取数据个数 in:加入的数据
20 | + 返回参数:算出的中位数
21 | ----------------------------------------------------------*/
22 | extern float Moving_Median(u8 item,u8 width_num,float in);
23 |
24 | /*----------------------------------------------------------
25 | + 实现功能:int类型数据求中位数
26 | + 调用参数:item:项目 width_num:求取数据个数 in:加入的数据
27 | + 返回参数:算出的中位数
28 | ----------------------------------------------------------*/
29 | extern int Moving_Median_int(u8 item,u8 width_num,int in_int);
30 |
31 | #endif
32 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved. */
33 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/height_ctrl.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 高度控制头文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef __HEIGHT_CTRL_H
16 | #define __HEIGHT_CTRL_H
17 |
18 | #include "stm32f4xx.h"
19 |
20 | /* 高度位置或速率PID控制量结构体 */
21 | typedef struct
22 | {
23 | float err;
24 | float err_old;
25 | float err_d;
26 | float err_i;
27 | float pid_out;
28 |
29 | } _st_height_pid_v;
30 | /* 高度位置或速率PID参数结构体 */
31 | typedef struct
32 | {
33 | float kp;
34 | float kd;
35 | float ki;
36 |
37 | } _st_height_pid;
38 |
39 | /* 气压计有接收到数据状态 */
40 | extern u8 baro_ctrl_start;
41 | /* 气压计高度 */
42 | extern float baro_height;
43 | /* 加速度在各方向的分量 */
44 | extern float wz_acc,north_acc,west_acc;
45 | /* 速度在各方向的分量 */
46 | extern float wz_speed,north_speed,west_speed;
47 | /* 定高高度速率PID输出量 */
48 | extern float height_ctrl_out;
49 |
50 | /* 最初启动气压定高 */
51 | extern float start_height;
52 | /*----------------------------------------------------------
53 | + 实现功能:油门控制高度
54 | + 调用参数:两次调用时间间隔,油门信号量
55 | ----------------------------------------------------------*/
56 | extern void Height_Ctrl(float T,float thr);
57 |
58 | /*----------------------------------------------------------
59 | + 实现功能:气压定高的PID参数初始化
60 | ----------------------------------------------------------*/
61 | extern void WZ_Speed_PID_Init(void);
62 |
63 | /*----------------------------------------------------------
64 | + 实现功能:高度的速度控制
65 | + 调用参数:两次调用时间间隔 遥控器油门控制量 期望垂直方向速度 垂直方向速度
66 | ----------------------------------------------------------*/
67 | extern void height_speed_ctrl(float T,float thr,float exp_z_speed,float );
68 |
69 | /*----------------------------------------------------------
70 | + 实现功能:气压计定高控制
71 | + 调用参数:两次调用时间间隔 遥控器油门控制量
72 | ----------------------------------------------------------*/
73 | extern void Baro_Ctrl(float T,float thr);
74 |
75 | /*----------------------------------------------------------
76 | + 实现功能:超声波定高的PID参数初始化
77 | ----------------------------------------------------------*/
78 | extern void Ultra_PID_Init(void);
79 |
80 | /*----------------------------------------------------------
81 | + 实现功能:超声波定高控制
82 | + 调用参数:两次调用时间间隔 遥控器油门控制量
83 | ----------------------------------------------------------*/
84 | extern void Ultra_Ctrl(float T,float thr);
85 |
86 | #endif
87 |
88 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/imu.h:
--------------------------------------------------------------------------------
1 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved.
2 | + 文件名 :imu.h
3 | + 描述 :姿态解算头文件
4 | 代码尽量做到逐行注释 代码有问题,及时加群交流 作者有偿支持对开源代码的完善 */
5 | #ifndef _IMU_H_
6 | #define _IMU_H_
7 |
8 | #include "stm32f4xx.h"
9 | #include "driver_parameter.h"
10 |
11 | /* 数据处理过程量结构体 */
12 | typedef struct
13 | {
14 | xyz_f_t err;
15 | xyz_f_t err_tmp;
16 | xyz_f_t err_lpf;
17 | xyz_f_t err_Int;
18 | xyz_f_t g;
19 |
20 | } ref_t;
21 | /* 加速度:由下向上方向的加速度在加速度计的分量 */
22 | extern xyz_f_t reference_v;
23 | /* 加速度:由南向北方向的加速度在加速度计的分量 *//* 加速度:由东向西方向的加速度在加速度计的分量 */
24 | extern xyz_f_t north,west;
25 | /* 最终计算出的姿态 单位 角度 */
26 | extern float IMU_Roll,IMU_Pitch,IMU_Yaw;
27 |
28 | /*----------------------------------------------------------
29 | + 实现功能:由任务调度调用周期5ms
30 | + 调用参数:两次调用时间差的一半
31 | ----------------------------------------------------------*/
32 | extern void Call_IMUupdate(float half_T);
33 |
34 | #endif
35 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved. */
36 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/init.c:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file init.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 系统初始化文件
7 | *@design 无人机研究小组
8 | 谭政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #include "stm32f4xx.h"
16 | #include "device_iic.h"
17 | #include "device_pwm_in.h"
18 | #include "driver_pwm_out.h"
19 | #include "driver_ms5611.h"
20 | #include "driver_mpu6050.h"
21 | #include "driver_ak8975.h"
22 | #include "driver_led.h"
23 | #include "data_transfer.h"
24 | #include "driver_ultrasonic.h"
25 | #include "Optical_Flow.h"
26 | #include "driver_GPS.h"
27 | #include "time.h"
28 | #include "ctrl.h"
29 | #include "device_beep.h"
30 | #include "device_power.h"
31 |
32 | /* 初始化结束标识 */
33 | u8 Init_Finish;
34 |
35 | /*----------------------------------------------------------
36 | + 实现功能:飞控初始化
37 | ----------------------------------------------------------*/
38 | void Light_Init()
39 | {
40 | /* 中断优先级组别设置 */
41 | NVIC_PriorityGroupConfig(NVIC_PriorityGroup_3);
42 | /* 开启定时器 */
43 | SysTick_Configuration();
44 | /* LED功能初始化 */
45 | LED_Init();
46 | /* BEEP功能初始化*/
47 | BEEP_Init();
48 | /* 电压采集功能初始化*/
49 | POWER_Init();
50 | /* 接收机信号采集初始化 */
51 | PWM_IN_Init();
52 | /* 初始化信号输出功能400HZ */
53 | PWM_Out_Init(400);
54 | /* I2C初始化 */
55 | I2c_Device_Init();
56 | /* 气压计初始化 */
57 | MS5611_Init();
58 | /* 加速度计、陀螺仪初始化,配置20hz低通 */
59 | MPU6050_Init(20);
60 | /* 磁力计初始化 */
61 | hard_error_ak8975 = AK8975_IS_EXIST();
62 | /* 数传初始化 */
63 | Data_transfer_init();
64 | /* 超声波初始化 */
65 | Ultrasonic_Init();
66 | /* 光流初始化 */
67 | Optical_Flow_init();
68 | /* GPS模块初始化 */
69 | GPS_Init();
70 | /* 参数初始化 */
71 | Para_Init();
72 | /* 时间统计初始化 */
73 | Cycle_Time_Init();
74 | /* 硬件故障指示 */
75 | if( hard_error_ak8975 ) LED_Mag_Err();
76 | if( hard_error_mpu6050 ) LED_MPU_Err();
77 | if( hard_error_ms5611 ) LED_MS5611_Err();
78 | /* 初始化结束标识 */
79 | Init_Finish = 1;
80 | }
81 |
82 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/init.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 系统初始化头文件
7 | *@design 无人机研究小组
8 | 谭政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _INIT_H_
16 | #define _INIT_H_
17 |
18 | #include "stm32f4xx.h"
19 |
20 | /* 初始化结束标识 */
21 | extern u8 Init_Finish;
22 |
23 | /*----------------------------------------------------------
24 | + 实现功能:飞控初始化
25 | ----------------------------------------------------------*/
26 | extern void Light_Init(void);
27 |
28 | #endif
29 |
30 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/main.c:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 主函数文件
7 | *@design 无人机研究小组 上传至github进行共同研发
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #include "init.h"
16 | #include "scheduler.h"
17 |
18 | /*----------------------------------------------------------
19 | + 实现功能:主函数
20 | ----------------------------------------------------------*/
21 | int32_t main(void)
22 | {
23 | /* 飞控初始化 */
24 | Light_Init();
25 | /* 主循环 */
26 | while(1)Main_Loop();
27 | }
28 |
29 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/mymath.h:
--------------------------------------------------------------------------------
1 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved.
2 | + 文件名 :mymath.h
3 | + 描述 :数学函数头文件
4 | 代码尽量做到逐行注释 代码有问题,及时加群交流 作者有偿支持对开源代码的完善 */
5 | #ifndef __MYMATH_H__
6 | #define __MYMATH_H__
7 |
8 | #include "stm32f4xx.h"
9 | #include "arm_math.h"
10 | #include "math.h"
11 |
12 | /* 数学函数简单宏定义函数 */
13 | #define ABS(x) ( (x)>0?(x):-(x) )
14 | #define LIMIT( x,min,max ) ( (x) < (min) ? (min) : ( (x) > (max) ? (max) : (x) ) )
15 | #define MIN(a, b) ((a) < (b) ? (a) : (b))
16 | #define MAX(a, b) ((a) > (b) ? (a) : (b))
17 |
18 | /*----------------------------------------------------------
19 | + 实现功能:死区控制:减去zoom值
20 | ----------------------------------------------------------*/
21 | extern float my_deathzoom(float x,float zoom);
22 |
23 | /*----------------------------------------------------------
24 | + 实现功能:死区控制:绝对值zoom内清零
25 | ----------------------------------------------------------*/
26 | extern float my_deathzoom_2(float x,float zoom);
27 |
28 | /*----------------------------------------------------------
29 | + 实现功能:角度范围控制在+-180角度
30 | ----------------------------------------------------------*/
31 | extern float To_180_degrees(float x);
32 |
33 | /*----------------------------------------------------------
34 | + 实现功能:快速反正切计算
35 | ----------------------------------------------------------*/
36 | extern float fast_atan2(float y, float x);
37 |
38 | #endif
39 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved. */
40 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/position_control.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief GPS位置控制头文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef __POSITION_CONTROL_H__
16 | #define __POSITION_CONTROL_H__
17 |
18 | #include "stm32f4xx.h"
19 | #include "driver_GPS.h"
20 |
21 | /* 悬停经纬度 坐标 单位 放大率10E5 */
22 | extern int STOP_longitude,STOP_latitude;
23 |
24 | /* 速度转换期望角度 */
25 | extern float expect_angle_pitch,expect_angle_roll;
26 |
27 | /* 当前位置 单位 放大率10E5 */
28 | extern int t_longitude,t_latitude;
29 |
30 | /* 方位 速度 放大率10E3 单位 毫米每秒 */
31 | extern int speed_longitude,speed_latitude;
32 |
33 | /* 飞行器 速度 单位毫米每秒 */
34 | extern float Speed_Front,Speed_Left;
35 | /* 飞行器位置向飞行器前方和左方偏移量 */
36 | extern float Dist_Front,Dist_Left;
37 | /* 期望速度的PID输出的角度控制量 */
38 | extern float expect_speed_pitch,expect_speed_roll;
39 | /* 期望姿态的PID输出 */
40 | extern float expect_angle_pitch,expect_angle_roll;
41 | /* 期望速度的PID输出 */
42 | extern float expect_speed_Front,expect_speed_Left;//
43 |
44 | /*----------------------------------------------------------
45 | + 实现功能:串级PID控制悬停
46 | + 调用参数:两次调用时间间隔
47 | ----------------------------------------------------------*/
48 | extern void PositionControl_Mode(float Timer_t);
49 |
50 | #endif
51 |
52 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/rc.h:
--------------------------------------------------------------------------------
1 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved.
2 | + 文件名 :rc.h
3 | + 描述 :遥控器通道数据处理头文件
4 | 代码尽量做到逐行注释 代码有问题,及时加群交流 作者有偿支持对开源代码的完善 */
5 | #ifndef _RC_H
6 | #define _RC_H
7 |
8 | #include "stm32f4xx.h"
9 |
10 | /* 滤波后的信号数据,范围是-500到+500 */
11 | extern float CH_filter[];
12 | /* 控制信号数据,范围是-500到+500 */
13 | extern s16 CH[];
14 | /* 8通道输入数传控制数据的数组1000-2000的控制信号 */
15 | extern u16 RX_CH[];
16 |
17 |
18 | /* 解锁判断标志
19 | 0未解锁 1已经解锁 */
20 | extern u8 unlocked_to_fly;
21 | /* 定高模式切换
22 | 0自稳 1气压定高 2超声定高 */
23 | /* 定点模式切换
24 | 1不定点 2记录返航点 3定点 */
25 | extern u8 height_ctrl_mode,position_ctrl_mode ;
26 | extern u8 position_ctrl_mode_old;
27 |
28 | /*----------------------------------------------------------
29 | + 实现功能:由任务调度调用周期2ms
30 | 接收机控制量数组:Mapped_CH 1000-1500-2000
31 | 数传控制量数组:RX_CH 1000-1500-2000
32 | 无控制量数组:STOP_CH 1000-1500-2000
33 | ----------------------------------------------------------*/
34 | extern void Call_RadioContrl(float inner_loop_time);
35 |
36 | /*----------------------------------------------------------
37 | + 实现功能:遥控信号虚拟看门狗,400ms内必须调用一次
38 | + 调用参数:控制信号类型:1为PWM信号 2为数传
39 | ----------------------------------------------------------*/
40 | extern void Call_RadioControl_Sign(u8 ch_mode);
41 |
42 | /*----------------------------------------------------------
43 | + 实现功能:控制模式判断 由任务调度调用周期50ms
44 | ----------------------------------------------------------*/
45 | extern void Call_RadioControl_Mode(void);
46 |
47 | #endif
48 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved. */
49 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/scheduler.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 任务调度头文件
7 | *@design 无人机研究小组
8 | 谭政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _SCHEDULER_H_
16 | #define _SCHEDULER_H_
17 |
18 | #include "stm32f4xx.h"
19 |
20 | /* 循环计数结构体 */
21 | typedef struct
22 | {
23 | /* 循环运行完毕标志 */
24 | u8 check_flag;
25 | /* 代码在预定周期内没有运行完错误计数 */
26 | u8 err_flag;
27 | /* 不同周期的执行任务独立计时 */
28 | s16 cnt_2ms;
29 | s16 cnt_5ms;
30 | s16 cnt_10ms;
31 | s16 cnt_20ms;
32 | s16 cnt_50ms;
33 | s16 cnt_100ms;
34 | } loop_t;
35 |
36 | /*----------------------------------------------------------
37 | + 实现功能:主循环 由主函数调用
38 | ----------------------------------------------------------*/
39 | extern void Main_Loop(void);
40 |
41 | /*----------------------------------------------------------
42 | + 实现功能:由Systick定时器调用 周期:1毫秒
43 | ----------------------------------------------------------*/
44 | extern void Call_Loop_timer(void);
45 |
46 | #endif
47 |
48 |
--------------------------------------------------------------------------------
/CAUC-Flight/applications/time.c:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file time.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 系统时间统计文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #include "stm32f4xx.h"
16 | #include "time.h"
17 | #include "init.h"
18 | #include "scheduler.h"
19 |
20 | /* 设置获取时间的数组数量 */
21 | #define GET_TIME_NUM (3)
22 |
23 | /* 换算成SYStick定时器计数微秒单位的比例 */
24 | #define TICK_US (1000000/TICK_PER_SECOND)
25 |
26 | /* 复位起的总中断次数 */
27 | volatile uint32_t sysTickUptime = 0;
28 |
29 | /* 计算两次点用时间间隔的数组 */
30 | volatile float Cycle_T[GET_TIME_NUM][3];
31 |
32 | /* 数组下标枚举体 */
33 | enum
34 | {
35 | NOW = 0,
36 | OLD,
37 | NEW,
38 | };
39 |
40 | /*----------------------------------------------------------
41 | + 实现功能:获取系统总运行时间
42 | + 返回参数:微秒
43 | ----------------------------------------------------------*/
44 | uint32_t GetSysTime_us(void)
45 | {
46 | /* 系统总运行 单位:毫秒 */
47 | register uint32_t ms;
48 | /* 用于返回的变量 单位:微秒 */
49 | u32 value;
50 | /* 获取系统总运行 单位:毫秒 */
51 | ms = sysTickUptime;
52 | /* 计算并获取为系统总运行 单位:微秒 */
53 | value = ms * TICK_US + (SysTick->LOAD - SysTick->VAL) * TICK_US / SysTick->LOAD;
54 | /* 返回参数 单位:微秒 */
55 | return value;
56 | }
57 |
58 | /*----------------------------------------------------------
59 | + 实现功能:延时
60 | + 调用参数:微秒
61 | ----------------------------------------------------------*/
62 | void Delay_us(uint32_t us)
63 | {
64 | /* 获取系统时钟 单位微秒 */
65 | uint32_t now = GetSysTime_us();
66 | /* 比较两次时间差 */
67 | while (GetSysTime_us() - now < us);
68 | }
69 |
70 | /*----------------------------------------------------------
71 | + 实现功能:延时
72 | + 调用参数:毫秒
73 | ----------------------------------------------------------*/
74 | void Delay_ms(uint32_t ms)
75 | {
76 | /* 延时微秒次数 */
77 | while (ms--) Delay_us(1000);
78 | }
79 |
80 | /*----------------------------------------------------------
81 | + 实现功能:计算两次点用时间间隔
82 | + 调用参数:统计时间项数组
83 | + 返回参数:两次时间间隔 单位:秒
84 | ----------------------------------------------------------*/
85 | float Call_timer_cycle(u8 item)
86 | {
87 | /* 上一次的时间 */
88 | Cycle_T[item][OLD] = Cycle_T[item][NOW];
89 | /* 本次的时间 */
90 | Cycle_T[item][NOW] = GetSysTime_us()/1000000.0f;
91 | /* 间隔的时间 单位:秒 */
92 | Cycle_T[item][NEW] = ( ( Cycle_T[item][NOW] - Cycle_T[item][OLD] ) );
93 | /* 两次时间间隔 单位:秒 */
94 | return Cycle_T[item][NEW];
95 | }
96 |
97 | /*----------------------------------------------------------
98 | + 实现功能:时间统计初始化
99 | ----------------------------------------------------------*/
100 | void Cycle_Time_Init()
101 | {
102 | /* 计算两次点用时间间隔数组清零 */
103 | for(u8 i=0; iBSRRL = Pin_BEEP
22 | #define BEEP_OFF GPIO_BEEP->BSRRH = Pin_BEEP
23 |
24 | /* BEEP 的GPIO宏定义 */
25 | #define RCC_BEEP RCC_AHB1Periph_GPIOA
26 | #define GPIO_BEEP GPIOA
27 | #define Pin_BEEP GPIO_Pin_0
28 |
29 | /*----------------------------------------------------------
30 | + 实现功能:控制BEEP初始化
31 | ----------------------------------------------------------*/
32 | extern void BEEP_Init(void);
33 |
34 | /*----------------------------------------------------------
35 | + 实现功能:控制BEEP 由任务调度调用周期1ms
36 | ----------------------------------------------------------*/
37 | extern void Call_BEEP_show(u8 duty);
38 |
39 | #endif
40 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/device_iic.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief IIC设备头文件
7 | *@design 无人机研究小组
8 | 谭政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _DEVICE_IIC_H
16 | #define _DEVICE_IIC_H
17 |
18 | #include "stm32f4xx.h"
19 |
20 | /* IIC延时长短 */
21 | extern volatile u8 I2C_FastMode;
22 |
23 | /*----------------------------------------------------------
24 | + 实现功能:IIC设备初始化
25 | ----------------------------------------------------------*/
26 | void I2c_Device_Init(void);
27 |
28 | /*----------------------------------------------------------
29 | + 实现功能:IIC写入单字节数据
30 | + 调用参数功能:设备,寄存器,数据
31 | + 返回参数功能:0正常 1异常
32 | ----------------------------------------------------------*/
33 | extern u8 IIC_Write_1Byte(u8 SlaveAddress,u8 REG_Address,u8 REG_data);
34 |
35 | /*----------------------------------------------------------
36 | + 实现功能:IIC读取单字节数据
37 | + 调用参数功能:设备,寄存器,数据
38 | + 返回参数功能:0正常 1异常
39 | ----------------------------------------------------------*/
40 | extern u8 IIC_Read_1Byte(u8 SlaveAddress,u8 REG_Address,u8 *REG_data);
41 |
42 | /*----------------------------------------------------------
43 | + 实现功能:IIC写入多字节数据
44 | + 调用参数功能:设备,寄存器,数据长度,数据
45 | + 返回参数功能:0正常 1异常
46 | ----------------------------------------------------------*/
47 | extern u8 IIC_Write_nByte(u8 SlaveAddress, u8 REG_Address, u8 len, u8 *buf);
48 |
49 | /*----------------------------------------------------------
50 | + 实现功能:IIC读取多字节数据
51 | + 调用参数功能:设备,寄存器,数据长度,数据
52 | + 返回参数功能:0正常 1异常
53 | ----------------------------------------------------------*/
54 | extern u8 IIC_Read_nByte(u8 SlaveAddress, u8 REG_Address, u8 len, u8 *buf);
55 |
56 | #endif
57 |
58 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/device_led.c:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file device_led.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief led设备文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #include "device_led.h"
16 | #include "stm32f4xx.h"
17 |
18 | /*----------------------------------------------------------
19 | + 实现功能:控制LED初始化
20 | ----------------------------------------------------------*/
21 | void LED_Init()
22 | {
23 | GPIO_InitTypeDef GPIO_InitStructure;
24 |
25 | RCC_AHB1PeriphClockCmd(RCC_LED,ENABLE);
26 |
27 | GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
28 | GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
29 | GPIO_InitStructure.GPIO_Speed = GPIO_Speed_25MHz;
30 | GPIO_InitStructure.GPIO_Pin = Pin_LED1| Pin_LED2| Pin_LED3| Pin_LED4;
31 | GPIO_Init(GPIO_LED, &GPIO_InitStructure);
32 |
33 | GPIO_SetBits(GPIO_LED, Pin_LED1);
34 | GPIO_SetBits(GPIO_LED, Pin_LED2);
35 | GPIO_SetBits(GPIO_LED, Pin_LED3);
36 | GPIO_SetBits(GPIO_LED, Pin_LED4);
37 | }
38 |
39 | /*----------------------------------------------------------
40 | + 实现功能:控制LED发光亮度 由任务调度调用周期1ms
41 | + 调用参数功能:发光亮度数组 0-20
42 | ----------------------------------------------------------*/
43 | void Call_LED_show( u8 duty[4] )
44 | {
45 | /* 计时值 */
46 | static u8 LED_cnt[4];
47 |
48 | /* 依次控制4个LED */
49 | for(u8 i=0; i<4; i++)
50 | {
51 | /* 计时器用于比较 */
52 | if( LED_cnt[i] < 19 )
53 | LED_cnt[i]++;
54 | else
55 | LED_cnt[i] = 0;
56 |
57 | /* LED开启状态控制 */
58 | if( LED_cnt[i] < duty[i] )
59 | {
60 | /* 依次控制4个LED */
61 | switch(i)
62 | {
63 | case 0:
64 | LED1_ON;
65 | break;
66 | case 1:
67 | LED2_ON;
68 | break;
69 | case 2:
70 | LED3_ON;
71 | break;
72 | case 3:
73 | LED4_ON;
74 | break;
75 | }
76 | }
77 | /* LED关断状态控制 */
78 | else
79 | {
80 | /* 依次控制4个LED */
81 | switch(i)
82 | {
83 | case 0:
84 | LED1_OFF;
85 | break;
86 | case 1:
87 | LED2_OFF;
88 | break;
89 | case 2:
90 | LED3_OFF;
91 | break;
92 | case 3:
93 | LED4_OFF;
94 | break;
95 | }
96 | }
97 | }
98 | }
99 |
100 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/device_led.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief led设备头文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _DEVICE_LED_H_
16 | #define _DEVICE_LED_H_
17 |
18 | #include "stm32f4xx.h"
19 |
20 | /* LED 电平宏定义 */
21 | #define LED1_OFF GPIO_LED->BSRRL = Pin_LED1
22 | #define LED1_ON GPIO_LED->BSRRH = Pin_LED1
23 | #define LED2_OFF GPIO_LED->BSRRL = Pin_LED2
24 | #define LED2_ON GPIO_LED->BSRRH = Pin_LED2
25 | #define LED3_OFF GPIO_LED->BSRRL = Pin_LED3
26 | #define LED3_ON GPIO_LED->BSRRH = Pin_LED3
27 | #define LED4_OFF GPIO_LED->BSRRL = Pin_LED4
28 | #define LED4_ON GPIO_LED->BSRRH = Pin_LED4
29 |
30 | /* LED 的GPIO宏定义 */
31 | #define RCC_LED RCC_AHB1Periph_GPIOE
32 | #define GPIO_LED GPIOE
33 | #define Pin_LED1 GPIO_Pin_3
34 | #define Pin_LED2 GPIO_Pin_2
35 | #define Pin_LED3 GPIO_Pin_1
36 | #define Pin_LED4 GPIO_Pin_0
37 |
38 | /*----------------------------------------------------------
39 | + 实现功能:控制LED初始化
40 | ----------------------------------------------------------*/
41 | extern void LED_Init(void);
42 |
43 | /*----------------------------------------------------------
44 | + 实现功能:控制LED发光亮度 由任务调度调用周期1ms
45 | + 调用参数功能:发光亮度数组 0-20
46 | ----------------------------------------------------------*/
47 | extern void Call_LED_show(u8 duty[4]);
48 |
49 | #endif
50 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/device_mpu6050.h:
--------------------------------------------------------------------------------
1 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved.
2 | + 文件名 device_mpu6050.h
3 | + 描述 :IMU传感器mpu6050设备头文件
4 | 代码尽量做到逐行注释 代码有问题,及时加群交流 作者有偿支持对开源代码的完善 */
5 | #ifndef _DEVICE_MPU6050_H
6 | #define _DEVICE_MPU6050_H
7 |
8 | #include "stm32f4xx.h"
9 |
10 | /* IMU传感器硬件故障 */
11 | extern u8 hard_error_mpu6050;
12 |
13 | /*----------------------------------------------------------
14 | + 实现功能:初始化 MPU6050 以进入可用状态
15 | + 调用参数功能:u16 lpf:设置低通滤波截止频率
16 | ----------------------------------------------------------*/
17 | extern void MPU6050_Init(u16);
18 |
19 | /*----------------------------------------------------------
20 | + 实现功能:由任务调度调用周期2ms
21 | + 调用参数功能:被读取的加速度计陀螺仪数据数组
22 | ----------------------------------------------------------*/
23 | extern void Call_MPU6050(u8 *buf14);
24 |
25 | #endif
26 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved. */
27 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/device_ms5611.c:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file device_ms5611.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 气压计设备文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #include "stm32f4xx.h"
16 | #include "device_ms5611.h"
17 | #include "device_iic.h"
18 |
19 | #define MS5611_ADDR 0x77 // MS5611 address
20 | #define CMD_RESET 0x1E // ADC reset command
21 | #define CMD_ADC_READ 0x00 // ADC read command
22 | #define CMD_ADC_CONV 0x40 // ADC conversion command
23 | #define CMD_ADC_D1 0x00 // ADC D1 conversion
24 | #define CMD_ADC_D2 0x10 // ADC D2 conversion
25 | #define CMD_ADC_256 0x00 // ADC OSR=256
26 | #define CMD_ADC_512 0x02 // ADC OSR=512
27 | #define CMD_ADC_1024 0x04 // ADC OSR=1024
28 | #define CMD_ADC_2048 0x06 // ADC OSR=2048
29 | #define CMD_ADC_4096 0x08 // ADC OSR=4096
30 | #define CMD_PROM_RD 0xA0 // Prom read command
31 | #define MS5611_OSR 0x08 // CMD_ADC_4096
32 |
33 | /*----------------------------------------------------------
34 | + 实现功能:气压计复位
35 | ----------------------------------------------------------*/
36 | void MS5611_Reset(void)
37 | {
38 | IIC_Write_1Byte(MS5611_ADDR, CMD_RESET, 1);
39 | }
40 |
41 | /*----------------------------------------------------------
42 | + 实现功能:读取气压计PORM存储器 并判断硬件故障
43 | ----------------------------------------------------------*/
44 | u8 MS5611_Read_Prom(uint16_t * ms5611_prom8)
45 | {
46 | uint8_t rxbuf[2] = { 0, 0 };
47 | u8 check = 0;
48 | u8 i;
49 |
50 | for (i = 0; i < 8; i++)
51 | {
52 | check += IIC_Read_nByte(MS5611_ADDR, CMD_PROM_RD + i * 2, 2, rxbuf); // send PROM READ command
53 | ms5611_prom8[i] = rxbuf[0] << 8 | rxbuf[1];
54 | }
55 | if(check==8)
56 | return 1;
57 | else
58 | return 0;
59 | }
60 |
61 | /*----------------------------------------------------------
62 | + 实现功能:读取测量数据
63 | ----------------------------------------------------------*/
64 | void MS5611_Read_measure(u8 * rxbuf)
65 | {
66 | IIC_Read_nByte( MS5611_ADDR, CMD_ADC_READ, 3, rxbuf );
67 | }
68 |
69 | /*----------------------------------------------------------
70 | + 实现功能:开始读取温度
71 | ----------------------------------------------------------*/
72 | void MS5611_Start_T(void)
73 | {
74 | IIC_Write_1Byte(MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D2 + MS5611_OSR, 1);
75 | }
76 |
77 | /*----------------------------------------------------------
78 | + 实现功能:开始读取气压
79 | ----------------------------------------------------------*/
80 | void MS5611_Start_P(void)
81 | {
82 | IIC_Write_1Byte(MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D1 + MS5611_OSR, 1);
83 | }
84 |
85 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/device_ms5611.h:
--------------------------------------------------------------------------------
1 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved.
2 | + 文件名 device_ms5611.h
3 | + 描述 :气压计设备头文件
4 | 代码尽量做到逐行注释 代码有问题,及时加群交流 作者有偿支持对开源代码的完善 */
5 | #ifndef _DEVICE_MS5611_H
6 | #define _DEVICE_MS5611_H
7 |
8 | #include "stm32f4xx.h"
9 |
10 | /*----------------------------------------------------------
11 | + 实现功能:气压计复位
12 | ----------------------------------------------------------*/
13 | extern void MS5611_Reset(void);
14 |
15 | /*----------------------------------------------------------
16 | + 实现功能:读取气压计PORM存储器 并判断硬件故障
17 | ----------------------------------------------------------*/
18 | extern u8 MS5611_Read_Prom(uint16_t * ms5611_prom8);
19 |
20 | /*----------------------------------------------------------
21 | + 实现功能:读取测量数据
22 | ----------------------------------------------------------*/
23 | extern void MS5611_Read_measure(u8 * rxbuf);
24 |
25 | /*----------------------------------------------------------
26 | + 实现功能:开始读取温度
27 | ----------------------------------------------------------*/
28 | extern void MS5611_Start_T(void);
29 |
30 | /*----------------------------------------------------------
31 | + 实现功能:开始读取气压
32 | ----------------------------------------------------------*/
33 | extern void MS5611_Start_P(void);
34 |
35 | #endif
36 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved. */
37 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/device_power.c:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file device_power.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 电池电压检测设备文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #include "device_power.h"
16 | #include "stm32f4xx.h"
17 |
18 | /*----------------------------------------------------------
19 | + 实现功能:电池电压检测初始化
20 | ----------------------------------------------------------*/
21 | void POWER_Init(void)
22 | {
23 | GPIO_InitTypeDef GPIO_InitStructure;
24 | ADC_CommonInitTypeDef ADC_CommonInitStructure;
25 | ADC_InitTypeDef ADC_InitStructure;
26 |
27 | RCC_AHB1PeriphClockCmd(RCC_POWER, ENABLE);//使能GPIOA时钟
28 | RCC_APB2PeriphClockCmd(RCC_ADC, ENABLE); //使能ADC1时钟
29 |
30 | //初始化ADC1通道1 IO口
31 | GPIO_InitStructure.GPIO_Pin = Pin_POWER;//PA1 通道1
32 | GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AN;//模拟输入
33 | GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN ;//不带上下拉
34 | GPIO_Init(GPIO_POWER, &GPIO_InitStructure);//初始化
35 |
36 | RCC_APB2PeriphResetCmd(RCC_ADC,ENABLE); //ADC1复位
37 | RCC_APB2PeriphResetCmd(RCC_ADC,DISABLE);//复位结束
38 |
39 |
40 | ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent;//独立模式
41 | ADC_CommonInitStructure.ADC_TwoSamplingDelay = ADC_TwoSamplingDelay_5Cycles;//两个采样阶段之间的延迟5个时钟
42 | ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled; //DMA失能
43 | ADC_CommonInitStructure.ADC_Prescaler = ADC_Prescaler_Div4;//预分频4分频。ADCCLK=PCLK2/4=84/4=21Mhz,ADC时钟最好不要超过36Mhz
44 | ADC_CommonInit(&ADC_CommonInitStructure);//初始化
45 |
46 | ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b;//12位模式
47 | ADC_InitStructure.ADC_ScanConvMode = DISABLE;//非扫描模式
48 | ADC_InitStructure.ADC_ContinuousConvMode = DISABLE;//关闭连续转换
49 | ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None;//禁止触发检测,使用软件触发
50 | ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;//右对齐
51 | ADC_InitStructure.ADC_NbrOfConversion = 1;//1个转换在规则序列中 也就是只转换规则序列1
52 | ADC_Init(ADC1, &ADC_InitStructure);//ADC初始化
53 |
54 |
55 | ADC_Cmd(ADC1, ENABLE);//开启AD转换器
56 | }
57 |
58 | /*----------------------------------------------------------
59 | + 实现功能:获取电源电压值
60 | ----------------------------------------------------------*/
61 | uint16_t Call_POWER_show(void)
62 | {
63 | //设置指定ADC的规则组通道,一个序列,采样时间
64 | ADC_RegularChannelConfig(ADC1, ADC_Channel_1, 1, ADC_SampleTime_480Cycles );//ADC1,ADC通道,480个周期,提高采样时间可以提高精确度
65 |
66 | ADC_SoftwareStartConv(ADC1);//使能指定的ADC1的软件转换启动功能
67 |
68 | while(!ADC_GetFlagStatus(ADC1, ADC_FLAG_EOC ));//等待转换结束
69 |
70 | return ADC_GetConversionValue(ADC1);//返回最近一次ADC1规则组的转换结果
71 | }
72 |
73 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/device_power.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 电池电压检测设备头文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _DEVICE_POWER_H_
16 | #define _DEVICE_POWER_H_
17 |
18 | #include "stm32f4xx.h"
19 |
20 | /* POWER 的GPIO宏定义 */
21 | #define RCC_POWER RCC_AHB1Periph_GPIOA
22 | #define RCC_ADC RCC_APB2Periph_ADC1
23 | #define GPIO_POWER GPIOA
24 | #define Pin_POWER GPIO_Pin_1
25 |
26 | /*----------------------------------------------------------
27 | + 实现功能:控制POWER初始化
28 | ----------------------------------------------------------*/
29 | extern void POWER_Init(void);
30 |
31 | /*----------------------------------------------------------
32 | + 实现功能:采集电池电压
33 | ----------------------------------------------------------*/
34 | extern uint16_t Call_POWER_show(void);
35 |
36 | #endif
37 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/device_pwm_in.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief PWM输入设备头文件
7 | *@design 无人机研究小组
8 | 谭政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _DEVICE_PWM_IN_H_
16 | #define _DEVICE_PWM_IN_H_
17 | #include "stm32f4xx.h"
18 |
19 | /*----------------------------------------------------------
20 | + 实现功能:PWM输入初始化
21 | ----------------------------------------------------------*/
22 | extern void PWM_IN_Init(void);
23 |
24 | #endif
25 |
26 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/device_pwm_out.h:
--------------------------------------------------------------------------------
1 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved.
2 | + 文件名 :device_pwm_out.h
3 | + 描述 :PWM输出设备头文件
4 | 代码尽量做到逐行注释 代码有问题,及时加群交流 作者有偿支持对开源代码的完善 */
5 | #ifndef _DEVICE_PWM_OUT_H_
6 | #define _DRVICE_PWM_OUT_H_
7 |
8 | #include "stm32f4xx.h"
9 |
10 | /*----------------------------------------------------------
11 | + 实现功能:PWM输出初始化
12 | + 调用参数功能:uint16_t hz:PWM输出的频率
13 | ----------------------------------------------------------*/
14 | extern void PWM_Out_Init(uint16_t hz);//400hz
15 |
16 | #endif
17 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved. */
18 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/device_timer.c:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file device_timer.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 定时器设备文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #include "stm32f4xx.h"
16 | #include "device_timer.h"
17 |
18 | /*----------------------------------------------------------
19 | + 实现功能:开启定时器
20 | ----------------------------------------------------------*/
21 | void SysTick_Configuration(void)
22 | {
23 | /* RCC时钟频率 */
24 | RCC_ClocksTypeDef rcc_clocks;
25 | /* SysTick两次中断期间计数次数 */
26 | uint32_t cnts;
27 | /* 获取RCC时钟频率 */
28 | RCC_GetClocksFreq(&rcc_clocks);
29 | /* 由时钟源及分频系数计算计数次数 */
30 | cnts = (uint32_t)rcc_clocks.HCLK_Frequency / TICK_PER_SECOND;
31 | cnts = cnts / 8;
32 | /* 设置SysTick计数次数 */
33 | SysTick_Config(cnts);
34 | /* 配置SysTick时钟源 */
35 | SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK_Div8);
36 | }
37 |
38 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/device_timer.h:
--------------------------------------------------------------------------------
1 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved.
2 | + 文件名 :device_timer.h
3 | + 描述 :定时器设备头文件
4 | 代码尽量做到逐行注释 代码有问题,及时加群交流 作者有偿支持对开源代码的完善 */
5 | #ifndef _DEVICE_TIMER_H_
6 | #define _DEVICE_TIMER_H_
7 |
8 | #include "stm32f4xx.h"
9 |
10 | /* 每秒钟SYStick定时器计数值 */
11 | #define TICK_PER_SECOND 1000
12 |
13 | /*----------------------------------------------------------
14 | + 实现功能:开启定时器
15 | ----------------------------------------------------------*/
16 | extern void SysTick_Configuration(void);
17 | #endif
18 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved. */
19 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/device_usart.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 串口设备头文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _DEVICE_USART_H
16 | #define _DEVICE_USART_H
17 | #include "stm32f4xx.h"
18 |
19 | /*----------------------------------------------------------
20 | + 实现功能:串口1初始化
21 | + 调用参数功能:
22 | - u32 bound:波特率
23 | - u8 Priority:中断主优先级
24 | - u8 SubPriority:中断从优先级
25 | - FunctionalState TXenable:发送中断使能
26 | - FunctionalState RXenable:就收中断使能
27 | ----------------------------------------------------------*/
28 | extern void Device_Usart1_ENABLE_Init(u32 bound,u8 Priority,u8 SubPriority,FunctionalState TXenable,FunctionalState RXenable);
29 |
30 | /*----------------------------------------------------------
31 | + 实现功能:串口2初始化
32 | + 调用参数功能:
33 | - u32 bound:波特率
34 | - u8 Priority:中断主优先级
35 | - u8 SubPriority:中断从优先级
36 | - FunctionalState TXenable:发送中断使能
37 | - FunctionalState RXenable:就收中断使能
38 | ----------------------------------------------------------*/
39 | extern void Device_Usart2_ENABLE_Init(u32 bound,u8 Priority,u8 SubPriority,FunctionalState TXenable,FunctionalState RXenable);
40 |
41 | /*----------------------------------------------------------
42 | + 实现功能:串口3初始化
43 | + 调用参数功能:
44 | - u32 bound:波特率
45 | - u8 Priority:中断主优先级
46 | - u8 SubPriority:中断从优先级
47 | - FunctionalState TXenable:发送中断使能
48 | - FunctionalState RXenable:就收中断使能
49 | ----------------------------------------------------------*/
50 | extern void Device_Usart3_ENABLE_Init(u32 bound,u8 Priority,u8 SubPriority,FunctionalState TXenable,FunctionalState RXenable);
51 |
52 | /*----------------------------------------------------------
53 | + 实现功能:串口4初始化
54 | + 调用参数功能:
55 | - u32 bound:波特率
56 | - u8 Priority:中断主优先级
57 | - u8 SubPriority:中断从优先级
58 | - FunctionalState TXenable:发送中断使能
59 | - FunctionalState RXenable:就收中断使能
60 | ----------------------------------------------------------*/
61 | extern void Device_Usart4_ENABLE_Init(u32 bound,u8 Priority,u8 SubPriority,FunctionalState TXenable,FunctionalState RXenable);
62 |
63 | /*----------------------------------------------------------
64 | + 实现功能:串口5初始化
65 | + 调用参数功能:
66 | - u32 bound:波特率
67 | - u8 Priority:中断主优先级
68 | - u8 SubPriority:中断从优先级
69 | - FunctionalState TXenable:发送中断使能
70 | - FunctionalState RXenable:就收中断使能
71 | ----------------------------------------------------------*/
72 | extern void Device_Usart5_ENABLE_Init(u32 bound,u8 Priority,u8 SubPriority,FunctionalState TXenable,FunctionalState RXenable);
73 |
74 | #endif
75 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/device_w25qxx.h:
--------------------------------------------------------------------------------
1 | #ifndef __DRIVER_AT45DB_H
2 | #define __DRIVER_AT45DB_H
3 | #include "stm32f4xx.h"
4 | #include "device_fatfs_conf.h" /* FatFs configuration options */
5 |
6 | #ifdef USE_SPI1
7 | #define SPI1_CLOCK RCC_APB2Periph_SPI1
8 | #define SPI1_AF GPIO_AF_SPI1
9 | #define SPI1_GPIO_CLOCK RCC_AHB1Periph_GPIOA
10 | #define SPI1_SCK_PORT GPIOA
11 | #define SPI1_MISO_PORT GPIOA
12 | #define SPI1_MOSI_PORT GPIOA
13 | #define SPI1_SCK_PIN GPIO_Pin_5
14 | #define SPI1_MISO_PIN GPIO_Pin_6
15 | #define SPI1_MOSI_PIN GPIO_Pin_7
16 | #define SPI1_SCK_SOURCE GPIO_PinSource5
17 | #define SPI1_MISO_SOURCE GPIO_PinSource6
18 | #define SPI1_MOSI_SOURCE GPIO_PinSource7
19 | #define SPI1_DMA_RX_ST DMA1_Stream3
20 | #define SPI1_DMA_RX_CHANNEL DMA_Channel_0
21 | #define SPI1_DMA_RX_FLAGS (DMA_IT_TEIF3 | DMA_IT_DMEIF3 | DMA_IT_FEIF3 | DMA_IT_TCIF3 | DMA_IT_HTIF3)
22 | #define SPI1_DMA_RX_IRQ DMA1_Stream3_IRQn
23 | #define SPI1_DMA_RX_HANDLER DMA1_Stream3_IRQHandler
24 | #define SPI1_DMA_TX_ST DMA1_Stream4
25 | #define SPI1_DMA_TX_CHANNEL DMA_Channel_0
26 | #define SPI1_DMA_TX_FLAGS (DMA_IT_TEIF4 | DMA_IT_DMEIF4 | DMA_IT_FEIF4 | DMA_IT_TCIF4 | DMA_IT_HTIF4)
27 | #endif
28 |
29 |
30 | void Flash_Init(void);
31 | void Flash_SectorErase(uint32_t address,uint8_t state);
32 | void Flash_PageRead(uint32_t address,uint8_t* buffer, uint32_t lenght);
33 | void Flash_PageWrite(uint32_t address,uint8_t* buffer, uint32_t lenght);
34 | void Flash_SectorsRead(uint32_t address,uint8_t *buffer,uint16_t count);
35 | void Flash_SectorsWrite(uint32_t address,uint8_t *buffer,uint16_t count);
36 | flash_info_t *Flash_GetInfo(void);
37 |
38 | #endif
39 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/integer.h:
--------------------------------------------------------------------------------
1 | /*-------------------------------------------*/
2 | /* Integer type definitions for FatFs module */
3 | /*-------------------------------------------*/
4 | #ifndef _FF_INTEGER
5 | #define _FF_INTEGER
6 |
7 | /* This type MUST be 8 bit */
8 | typedef unsigned char BYTE;
9 |
10 | /* These types MUST be 16 bit */
11 | typedef short SHORT;
12 | typedef unsigned short WORD;
13 | typedef unsigned short WCHAR;
14 |
15 | /* These types MUST be 16 bit or 32 bit */
16 | typedef int INT;
17 | typedef unsigned int UINT;
18 |
19 | /* These types MUST be 32 bit */
20 | typedef long LONG;
21 | typedef unsigned long DWORD;
22 |
23 | #endif
24 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/usbd_user_hid.c:
--------------------------------------------------------------------------------
1 | /*----------------------------------------------------------------------------
2 | * RL-ARM - USB
3 | *----------------------------------------------------------------------------
4 | * Name: usbd_user_hid.c
5 | * Purpose: Human Interface Device Class User module
6 | * Rev.: V4.70
7 | *----------------------------------------------------------------------------
8 | * This code is part of the RealView Run-Time Library.
9 | * Copyright (c) 2004-2013 KEIL - An ARM Company. All rights reserved.
10 | *---------------------------------------------------------------------------*/
11 |
12 | #include "RTL.h"
13 | #include
14 | #include /* STM32F4xx Definitions */
15 | #define __NO_USB_LIB_C
16 | #include "usb_config.c"
17 | #include "data_transfer.h"
18 | #include "usbd_user_hid.h"
19 |
20 | u8 HID_SEND_TIMEOUT = 5; //hid发送不足一帧时,等待HID_SEND_TIMEOUT周期进行发送
21 | u8 hid_datatemp[256]; //hid环形缓冲区
22 | u8 hid_datatemp_begin = 0; //环形缓冲区数据指针,指向应当发送的数据
23 | u8 hid_datatemp_end = 0; //环形缓冲区数据结尾
24 | u8 hid_data2send[64]; //hid发送缓存,一个hid数据帧64字节,第一字节表示有效数据字节数,0-63,后面是数据,最多63字节
25 |
26 | void Usb_Hid_Init (void)
27 | {
28 | usbd_init();
29 | usbd_connect(__TRUE);
30 | }
31 | void Usb_Hid_Adddata(u8 *dataToSend , u8 length)
32 | {
33 | for(u8 i=0; i hid_datatemp_begin)
43 | {
44 | if((hid_datatemp_end - hid_datatemp_begin) >= 63)
45 | {
46 | notfull_timeout = 0;
47 | hid_data2send[0] = 63;
48 | for(u8 i=0; i<63; i++)
49 | {
50 | hid_data2send[i+1] = hid_datatemp[hid_datatemp_begin++];
51 | }
52 | usbd_hid_get_report_trigger(0, hid_data2send, 64); //send
53 | }
54 | else
55 | {
56 | notfull_timeout++;
57 | if(notfull_timeout == HID_SEND_TIMEOUT)
58 | {
59 | notfull_timeout = 0;
60 | hid_data2send[0] = hid_datatemp_end - hid_datatemp_begin;
61 | for(u8 i=0; i<63; i++)
62 | {
63 | if(i= 63)
76 | {
77 | notfull_timeout = 0;
78 | hid_data2send[0] = 63;
79 | for(u8 i=0; i<63; i++)
80 | {
81 | hid_data2send[i+1] = hid_datatemp[hid_datatemp_begin++];
82 | }
83 | usbd_hid_get_report_trigger(0, hid_data2send, 64); //send
84 | }
85 | else
86 | {
87 | notfull_timeout++;
88 | if(notfull_timeout == HID_SEND_TIMEOUT)
89 | {
90 | notfull_timeout = 0;
91 | hid_data2send[0] = 256 - hid_datatemp_begin + hid_datatemp_end;
92 | for(u8 i=0; i<63; i++)
93 | {
94 | if(i<256 - hid_datatemp_begin + hid_datatemp_end)
95 | hid_data2send[i+1] = hid_datatemp[(u8)(hid_datatemp_begin+i)];
96 | else
97 | hid_data2send[i+1] = 0;
98 | }
99 | hid_datatemp_begin = hid_datatemp_end;
100 | usbd_hid_get_report_trigger(0, hid_data2send, 64); //dend
101 | }
102 | }
103 | }
104 | }
105 |
106 | int usbd_hid_get_report (U8 rtype, U8 rid, U8 *buf, U8 req)
107 | {
108 | switch (rtype)
109 | {
110 | case HID_REPORT_INPUT:
111 | switch (rid)
112 | {
113 | case 0:
114 | switch (req)
115 | {
116 | case USBD_HID_REQ_EP_CTRL:
117 | case USBD_HID_REQ_PERIOD_UPDATE:
118 | return 64;
119 | case USBD_HID_REQ_EP_INT:
120 | break;
121 | }
122 | break;
123 | }
124 | break;
125 | case HID_REPORT_FEATURE:
126 | return (1);
127 | }
128 | return (0);
129 | }
130 |
131 | void usbd_hid_set_report (U8 rtype, U8 rid, U8 *buf, int len, U8 req) {
132 |
133 | switch (rtype) {
134 | case HID_REPORT_OUTPUT:
135 | for(u8 i = 1; i<=(*(buf)); i++)
136 | DT_Data_Receive_Prepare(*(buf+i)); //hid接收到数据会调用此函数
137 | break;
138 | case HID_REPORT_FEATURE:
139 | //feat = buf[0];
140 | break;
141 | }
142 | }
143 |
--------------------------------------------------------------------------------
/CAUC-Flight/devices/usbd_user_hid.h:
--------------------------------------------------------------------------------
1 | #ifndef _USBD_USER_HID_H
2 | #define _USBD_USER_HID_H
3 |
4 | #include "stm32f4xx.h"
5 |
6 | extern void Usb_Hid_Init(void) ;
7 | void Usb_Hid_Adddata(u8 *dataToSend , u8 length);
8 | void Usb_Hid_Send(void);
9 |
10 | #endif
11 |
12 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/database.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 数据结构头文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _DATABASE_H_
16 | #define _DATABASE_H_
17 |
18 | #include "stm32f4xx.h"
19 |
20 | /* 加速度计、陀螺仪数据枚举体 */
21 | enum
22 | {
23 | A_X = 0,
24 | A_Y ,
25 | A_Z ,
26 | G_Y ,
27 | G_X ,
28 | G_Z ,
29 | TEM ,
30 | ITEMS ,
31 | };
32 |
33 | /* 遥控控制通道数组枚举体 */
34 | enum
35 | {
36 | ROL= 0,
37 | PIT ,
38 | THR ,
39 | YAW ,
40 | AUX1 ,
41 | AUX2 ,
42 | AUX3 ,
43 | AUX4 ,
44 | };
45 |
46 | /* PID参数结构体 */
47 | typedef struct
48 | {
49 | float kp;
50 | float kd;
51 | float ki;
52 | float kdamp;
53 | } pid_t;
54 |
55 | /* XYZ结构体 */
56 | typedef struct
57 | {
58 | float x;
59 | float y;
60 | float z;
61 | } xyz_f_t;
62 |
63 | /* xyz结构体 */
64 | typedef struct
65 | {
66 | s16 x;
67 | s16 y;
68 | s16 z;
69 |
70 | } xyz_s16_t;
71 |
72 | /* 传感器数据共用体 */
73 | typedef union
74 | {
75 | uint8_t raw_data[64];
76 | struct
77 | {
78 | xyz_f_t Accel;
79 | xyz_f_t Gyro;
80 | xyz_f_t Mag;
81 | xyz_f_t vec_3d_cali;
82 | uint32_t Baro;
83 | float Acc_Temperature;
84 | float Gyro_Temperature;
85 | } Offset;
86 | } sensor_setup_t;
87 |
88 | /* PID在3轴上的控制量结构体 */
89 | typedef struct
90 | {
91 | pid_t roll;
92 | pid_t pitch;
93 | pid_t yaw;
94 | } pid_group_t;
95 |
96 | /* PID总的控制量共用体 */
97 | typedef union
98 | {
99 | uint8_t raw_data[192];
100 | struct
101 | {
102 | pid_group_t ctrl1;
103 | pid_group_t ctrl2;
104 | pid_t hc_sp;
105 | pid_t hc_height;
106 | pid_t ctrl3;
107 | pid_t ctrl4;
108 | pid_t ctrl5;
109 | pid_t ctrl6;
110 | } groups;
111 |
112 | } pid_setup_t;
113 |
114 | /* 磁力计数组:采样值,偏移值,纠正后的值 */
115 | typedef struct
116 | {
117 | xyz_s16_t Mag_Adc; //采样值
118 | xyz_f_t Mag_Offset; //偏移值
119 | xyz_f_t Mag_Val; //纠正后的值
120 | } ak8975_t;
121 |
122 | /* IMU传感器mpu6050数组*/
123 | typedef struct
124 | {
125 | /* 传感器校准标志 */
126 | char Acc_CALIBRATE;
127 | char Gyro_CALIBRATE;
128 | /* IMU数据 */
129 | xyz_s16_t Acc_I16;
130 | xyz_s16_t Gyro_I16;
131 | xyz_f_t Acc;
132 | xyz_f_t Gyro;
133 | xyz_f_t Gyro_deg;
134 | /* IMU补偿 */
135 | xyz_f_t Acc_Offset;
136 | xyz_f_t Gyro_Offset;
137 | xyz_f_t vec_3d_cali;
138 | /* 温度补偿 */
139 | float Acc_Temprea_Offset;
140 | float Gyro_Temprea_Offset;
141 | float Gyro_Temprea_Adjust;
142 | float ACC_Temprea_Adjust;
143 | /* 读取温度信息及滤波 */
144 | s16 Tempreature;
145 | float TEM_LPF;
146 | float Ftempreature;
147 | } MPU6050_STRUCT;
148 |
149 | #endif
150 |
151 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_ak8975.c:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file driver_ak8975.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 磁力计(电子罗盘)驱动文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #include "stm32f4xx.h"
16 | #include "device_ak8975.h"
17 | #include "driver_ak8975.h"
18 | #include "database.h"
19 | #include "driver_parameter.h"
20 | #include "mymath.h"
21 |
22 | /* 校准磁力计时持续时间 */
23 | #define CALIBRATING_MAG_CYCLES 3000
24 | /* 磁力计均值滤波数组 */
25 | #define MAG_FILTER_NUM 20
26 |
27 | /* 磁力计数组:采样值,偏移值,纠正后的值 */
28 | ak8975_t ak8975 = { {0,0,0},{-1,-1,-1},{0,0,0} };
29 | /* 磁力计硬件故障 */
30 | u8 hard_error_ak8975;
31 | /* 磁力计校准标识 */
32 | u8 Mag_CALIBRATED = 0;
33 |
34 | /*----------------------------------------------------------
35 | + 实现功能:磁力计采样触发
36 | + 返回值:磁力计运行状态
37 | ----------------------------------------------------------*/
38 | uint8_t AK8975_IS_EXIST(void)
39 | {
40 | return AK8975_IS_RUN();
41 | }
42 |
43 | /*----------------------------------------------------------
44 | + 实现功能:判断是否磁力计校准
45 | ----------------------------------------------------------*/
46 | void AK8975_Set_CalOffset(void)
47 | {
48 | /* 校准前的缺省值 */
49 | static xyz_f_t MagMAX = { -100 , -100 , -100 }, MagMIN = { 100 , 100 , 100 };
50 | /* 校准时间计数 */
51 | static uint16_t cnt_m=0;
52 |
53 | /* 判断是否磁力计校准 */
54 | if(Mag_CALIBRATED)
55 | {
56 | /* 校准时间计数 */
57 | cnt_m++;
58 | /* 保存单一方向最值 */
59 | if(ABS(ak8975.Mag_Adc.x)<400)
60 | {
61 | MagMAX.x = MAX(ak8975.Mag_Adc.x, MagMAX.x);
62 | MagMIN.x = MIN(ak8975.Mag_Adc.x, MagMIN.x);
63 | }
64 | /* 保存单一方向最值 */
65 | if(ABS(ak8975.Mag_Adc.y)<400)
66 | {
67 | MagMAX.y = MAX(ak8975.Mag_Adc.y, MagMAX.y);
68 | MagMIN.y = MIN(ak8975.Mag_Adc.y, MagMIN.y);
69 | }
70 | /* 保存单一方向最值 */
71 | if(ABS(ak8975.Mag_Adc.z)<400)
72 | {
73 | MagMAX.z = MAX(ak8975.Mag_Adc.z, MagMAX.z);
74 | MagMIN.z = MIN(ak8975.Mag_Adc.z, MagMIN.z);
75 | }
76 | /* 校准时间到 */
77 | if(cnt_m == CALIBRATING_MAG_CYCLES)
78 | {
79 | /* 保存校准后的数据 */
80 | ak8975.Mag_Offset.x = (MagMAX.x + MagMIN.x)/2;
81 | ak8975.Mag_Offset.y = (MagMAX.y + MagMIN.y)/2;
82 | ak8975.Mag_Offset.z = (MagMAX.z + MagMIN.z)/2;
83 | /* 保存数据 */
84 | Param_SaveMagOffset(&ak8975.Mag_Offset);
85 | /* 校准、校准时间清零 */
86 | cnt_m = 0;
87 | Mag_CALIBRATED = 0;
88 | }
89 | }
90 | }
91 |
92 | /*----------------------------------------------------------
93 | + 实现功能:由任务调度调用周期10ms
94 | ----------------------------------------------------------*/
95 | void Call_AK8975(void)
96 | {
97 | /* 滤波滑动窗口临时数组 */
98 | static xyz_f_t Mag_Adc_fill[MAG_FILTER_NUM];
99 | /* 滤波滑动窗口总和 */
100 | static xyz_f_t Mag_Adc_fill_total;
101 | /* 滤波滑动窗口数组下标 */
102 | static char temp_i;
103 |
104 | /* 磁力计采样原始数据 */
105 | ak8975.Mag_Adc.x = AK8975_Read_Mag_X();
106 | ak8975.Mag_Adc.y = AK8975_Read_Mag_Y();
107 | ak8975.Mag_Adc.z = AK8975_Read_Mag_Z();
108 |
109 | /* 更新滤波滑动窗口临时数组 */
110 | Mag_Adc_fill[temp_i].x = ak8975.Mag_Adc.x;
111 | Mag_Adc_fill[temp_i].y = ak8975.Mag_Adc.y;
112 | Mag_Adc_fill[temp_i].z = ak8975.Mag_Adc.z;
113 | /* 滑动窗口滤波数组下标移位 */
114 | temp_i++;
115 | if(temp_i>=MAG_FILTER_NUM)temp_i=0;
116 |
117 | /* 更新滑动窗口滤波数据总和 */
118 | Mag_Adc_fill_total.x+=ak8975.Mag_Adc.x;
119 | Mag_Adc_fill_total.y+=ak8975.Mag_Adc.y;
120 | Mag_Adc_fill_total.z+=ak8975.Mag_Adc.z;
121 | Mag_Adc_fill_total.x-=Mag_Adc_fill[temp_i].x;
122 | Mag_Adc_fill_total.y-=Mag_Adc_fill[temp_i].y;
123 | Mag_Adc_fill_total.z-=Mag_Adc_fill[temp_i].z;
124 |
125 | /* 得出处理后的数据 */
126 | ak8975.Mag_Val.x = Mag_Adc_fill_total.x / MAG_FILTER_NUM;
127 | ak8975.Mag_Val.y = Mag_Adc_fill_total.y / MAG_FILTER_NUM;
128 | ak8975.Mag_Val.z = Mag_Adc_fill_total.z / MAG_FILTER_NUM;
129 |
130 | /* 减去偏置校准 */
131 | ak8975.Mag_Val.x = (ak8975.Mag_Val.x - ak8975.Mag_Offset.x) ;
132 | ak8975.Mag_Val.y = (ak8975.Mag_Val.y - ak8975.Mag_Offset.y) ;
133 | ak8975.Mag_Val.z = (ak8975.Mag_Val.z - ak8975.Mag_Offset.z) ;
134 |
135 | /* 判断是否磁力计校准 */
136 | AK8975_Set_CalOffset();
137 | /* 磁力计采样触发 */
138 | AK8975_IS_RUN();
139 | }
140 |
141 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_ak8975.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 磁力计(电子罗盘)驱动头文件
7 | *@design 无人机研究小组
8 | 谭政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _DRIVER_AK8975_H_
16 | #define _DRIVER_AK8975_H_
17 |
18 | #include "stm32f4xx.h"
19 | #include "database.h"
20 |
21 | /* 磁力计数组:采样值,偏移值,纠正后的值 */
22 | extern ak8975_t ak8975;
23 | /* 磁力计硬件故障 */
24 | extern u8 hard_error_ak8975;
25 | /* 磁力计校准标识 */
26 | extern u8 Mag_CALIBRATED;
27 |
28 | /*----------------------------------------------------------
29 | + 实现功能:磁力计采样触发
30 | + 返回值:磁力计运行状态
31 | ----------------------------------------------------------*/
32 | extern uint8_t AK8975_IS_EXIST(void);
33 |
34 | /*----------------------------------------------------------
35 | + 实现功能:由任务调度调用周期10ms
36 | ----------------------------------------------------------*/
37 | extern void Call_AK8975(void);
38 |
39 | #endif
40 |
41 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_beep.c:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file driver_beep.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 蜂鸣器指示灯状态控制文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #include "stm32f4xx.h"
16 | #include "driver_beep.h"
17 | #include "device_beep.h"
18 | #include "driver_power.h"
19 | #include "ctrl.h"
20 |
21 | /* BEEP范围是0-20 */
22 | u8 BEEP_Brightness;
23 |
24 | /*----------------------------------------------------------
25 | + 实现功能:由任务调度调用周期50ms
26 | ----------------------------------------------------------*/
27 | void Call_BEEP_duty()
28 | {
29 | /* 锁定时蜂鸣器鸣响时间 */
30 | static uint8_t lock_showtime = 0;
31 | /* 解锁时蜂鸣器鸣响时间 */
32 | static uint8_t unlock_showtime = 0 , unlock_showtime_1 = 0;
33 |
34 |
35 | /* 低电压状态指示 */
36 | if( LowPower_Flag )
37 | {
38 | BEEP_Brightness = 20;
39 | }
40 | /* 未解锁状态指示 */
41 | else if(!unlocked_to_fly)
42 | {
43 | lock_showtime = 0;
44 | if( unlock_showtime < 20)
45 | {
46 | unlock_showtime ++;
47 | /* 指示灯状态数组赋值 */
48 | BEEP_Brightness = 20;
49 | }
50 | else
51 | BEEP_Brightness = 0;
52 | }
53 | /* 解锁后状态指示 */
54 | else
55 | {
56 | unlock_showtime = 0;
57 | unlock_showtime_1++;
58 | if( lock_showtime < 40)
59 | {
60 | lock_showtime ++;
61 | /* 指示灯状态数组赋值 */
62 | BEEP_Brightness = 20;
63 | }
64 | else if( unlock_showtime_1 < 5 && Thr_Low)
65 | {
66 | BEEP_Brightness = 20;
67 | }
68 | else if( unlock_showtime_1 < 200)
69 | {
70 | BEEP_Brightness = 0;
71 | }
72 | else
73 | unlock_showtime_1 = 0;
74 | }
75 | }
76 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_beep.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 蜂鸣器指示灯状态控制头文件
7 | *@design 无人机研究小组
8 | 谭政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _DRIVER_BEEP_H_
16 | #define _DRIVER_BEEP_H_
17 |
18 | #include "stm32f4xx.h"
19 | #include "device_led.h"
20 |
21 | /* 每个BEEP范围是0-20 */
22 | extern u8 BEEP_Brightness;
23 |
24 | /*----------------------------------------------------------
25 | + 实现功能:由任务调度调用周期50ms
26 | ----------------------------------------------------------*/
27 | extern void Call_BEEP_duty(void);
28 |
29 | /*----------------------------------------------------------
30 | + 实现功能:MPU故障指示
31 | ----------------------------------------------------------*/
32 | extern void BEEP_MPU_Err(void);
33 |
34 | /*----------------------------------------------------------
35 | + 实现功能:磁力计故障指示
36 | ----------------------------------------------------------*/
37 | extern void BEEP_Mag_Err(void);
38 |
39 | /*----------------------------------------------------------
40 | + 实现功能:气压计故障指示
41 | ----------------------------------------------------------*/
42 | extern void BEEP_MS5611_Err(void);
43 |
44 | #endif
45 |
46 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_disk.c:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/zhangdashuo/CAUC_Flight/dc2cf767939d95d29d464dac213ef2f41daab39f/CAUC-Flight/drivers/driver_disk.c
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_disk.h:
--------------------------------------------------------------------------------
1 | /*-----------------------------------------------------------------------/
2 | / Low level disk interface modlue include file (C)ChaN, 2014 /
3 | /-----------------------------------------------------------------------*/
4 | #ifndef _DRIVER_DISKIO_H
5 | #define _DRIVER_DISKIO_H
6 |
7 | #include "integer.h"
8 |
9 | #define _USE_WRITE 1 /* 1: Enable disk_write function */
10 | #define _USE_IOCTL 1 /* 1: Enable disk_ioctl fucntion */
11 |
12 | /* Disk Status Bits (DSTATUS) */
13 | #define STA_NOINIT 0x01 /* Drive not initialized */
14 | #define STA_NODISK 0x02 /* No medium in the drive */
15 | #define STA_PROTECT 0x04 /* Write protected */
16 | /* Command code for disk_ioctrl fucntion */
17 | /* Generic command (Used by FatFs) */
18 | #define CTRL_SYNC 0 /* Complete pending write process (needed at _FS_READONLY == 0) */
19 | #define GET_SECTOR_COUNT 1 /* Get media size (needed at _USE_MKFS == 1) */
20 | #define GET_SECTOR_SIZE 2 /* Get sector size (needed at _MAX_SS != _MIN_SS) */
21 | #define GET_BLOCK_SIZE 3 /* Get erase block size (needed at _USE_MKFS == 1) */
22 | #define CTRL_TRIM 4 /* Inform device that the data on the block of sectors is no longer used (needed at _USE_TRIM == 1) */
23 | /* Generic command (Not used by FatFs) */
24 | #define CTRL_POWER 5 /* Get/Set power status */
25 | #define CTRL_LOCK 6 /* Lock/Unlock media removal */
26 | #define CTRL_EJECT 7 /* Eject media */
27 | #define CTRL_FORMAT 8 /* Create physical format on the media */
28 | /* MMC/SDC specific ioctl command */
29 | #define MMC_GET_TYPE 10 /* Get card type */
30 | #define MMC_GET_CSD 11 /* Get CSD */
31 | #define MMC_GET_CID 12 /* Get CID */
32 | #define MMC_GET_OCR 13 /* Get OCR */
33 | #define MMC_GET_SDSTAT 14 /* Get SD status */
34 | /* ATA/CF specific ioctl command */
35 | #define ATA_GET_REV 20 /* Get F/W revision */
36 | #define ATA_GET_MODEL 21 /* Get model name */
37 | #define ATA_GET_SN 22 /* Get serial number */
38 |
39 | /* Status of Disk Functions */
40 | typedef BYTE DSTATUS;
41 |
42 | /* Results of Disk Functions */
43 | typedef enum
44 | {
45 | RES_OK = 0, /* 0: Successful */
46 | RES_ERROR, /* 1: R/W Error */
47 | RES_WRPRT, /* 2: Write Protected */
48 | RES_NOTRDY, /* 3: Not Ready */
49 | RES_PARERR /* 4: Invalid Parameter */
50 | } DRESULT;
51 |
52 | /* Prototypes for disk control functions */
53 | DSTATUS disk_initialize (BYTE pdrv);
54 | DSTATUS disk_status (BYTE pdrv);
55 | DRESULT disk_read (BYTE pdrv, BYTE* buff, DWORD sector, UINT count);
56 | DRESULT disk_write (BYTE pdrv, const BYTE* buff, DWORD sector, UINT count);
57 | DRESULT disk_ioctl (BYTE pdrv, BYTE cmd, void* buff);
58 |
59 | #endif
60 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_led.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief LED指示灯状态控制头文件
7 | *@design 无人机研究小组
8 | 谭政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _DRIVER_LED_H_
16 | #define _DRIVER_LED_H_
17 |
18 | #include "stm32f4xx.h"
19 | #include "device_led.h"
20 |
21 | /* 每个LED亮度范围是0-20 */
22 | extern u8 LED_Brightness[4];
23 |
24 | /*----------------------------------------------------------
25 | + 实现功能:由任务调度调用周期50ms
26 | ----------------------------------------------------------*/
27 | extern void Call_LED_duty(void);
28 |
29 | /*----------------------------------------------------------
30 | + 实现功能:MPU故障指示
31 | ----------------------------------------------------------*/
32 | extern void LED_MPU_Err(void);
33 |
34 | /*----------------------------------------------------------
35 | + 实现功能:磁力计故障指示
36 | ----------------------------------------------------------*/
37 | extern void LED_Mag_Err(void);
38 |
39 | /*----------------------------------------------------------
40 | + 实现功能:气压计故障指示
41 | ----------------------------------------------------------*/
42 | extern void LED_MS5611_Err(void);
43 |
44 | #endif
45 |
46 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_lidarlite.c:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/zhangdashuo/CAUC_Flight/dc2cf767939d95d29d464dac213ef2f41daab39f/CAUC-Flight/drivers/driver_lidarlite.c
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_lidarlite.h:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/zhangdashuo/CAUC_Flight/dc2cf767939d95d29d464dac213ef2f41daab39f/CAUC-Flight/drivers/driver_lidarlite.h
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_mpu6050.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief IMU传感器mpu6050驱动头文件
7 | *@design 无人机研究小组
8 | 谭政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _DRIVER_MPU6050_H
16 | #define _DRIVER_MPU6050_H
17 |
18 | #include "stm32f4xx.h"
19 | #include "database.h"
20 | #include "device_mpu6050.h"
21 |
22 | /* MPU6050结构体 */
23 | extern MPU6050_STRUCT mpu6050;
24 |
25 | /*----------------------------------------------------------
26 | + 实现功能:由任务调度调用周期2ms
27 | ----------------------------------------------------------*/
28 | extern void Call_MPU6050_Data_Prepare(float T);
29 |
30 | #endif
31 |
32 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_ms5611.c:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file driver_ms5611.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 气压计驱动文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #include "stm32f4xx.h"
16 | #include "driver_ms5611.h"
17 | #include "device_ms5611.h"
18 | #include "filter.h"
19 | #include "database.h"
20 | #include "time.h"
21 | #define BARO_CAL_CNT 200
22 |
23 | /* 气压计计算高度,单位mm(毫米) */
24 | int32_t baroAlt,baroAltOld;
25 | /* 气压计计算速度单位mm/s */
26 | float baro_alt_speed;
27 | /* 读取的气压计PORM存储器数组 */
28 | static uint16_t ms5611_prom8[8];
29 | /* 读取的温度、压强数据数组 */
30 | static uint8_t t_rxbuf[3],p_rxbuf[3];
31 |
32 | /*----------------------------------------------------------
33 | + 实现功能:气压计数据更新 由任务调度调用周期10ms
34 | ----------------------------------------------------------*/
35 | int MS5611_Update(void)
36 | {
37 | /* 气压计状态位 */
38 | static int state = 0;
39 | if (state)
40 | {
41 | /* 读取上次测量的气压 */
42 | MS5611_Read_measure(p_rxbuf);
43 | /* 开始读取温度 */
44 | MS5611_Start_T();
45 | /* 气压计高度计算 */
46 | MS5611_BaroAltCalculate();
47 | /* 气压计状态位 */
48 | state = 0;
49 | }
50 | else
51 | {
52 | /* 读取上次测量的温度 */
53 | MS5611_Read_measure(t_rxbuf);
54 | /* 开始读取气压 */
55 | MS5611_Start_P();
56 | /* 气压计状态位 */
57 | state = 1;
58 | }
59 | /* 返回状态值 */
60 | return (state);
61 | }
62 |
63 |
64 | /* 温度 */
65 | uint32_t ms5611_ut;
66 | /* 气压 */
67 | uint32_t ms5611_up;
68 | /* 气压补偿 */
69 | int32_t baro_Offset=0;
70 | /* 气压计温度 */
71 | float temperature_5611;
72 | /*----------------------------------------------------------
73 | + 实现功能:气压计高度计算
74 | ----------------------------------------------------------*/
75 | void MS5611_BaroAltCalculate(void)
76 | {
77 | static u8 baro_start;
78 | int32_t temperature, off2 = 0, sens2 = 0, delt;
79 | int32_t pressure;
80 | float alt_3;
81 | int32_t dT;
82 | int64_t off;
83 | int64_t sens;
84 | static vs32 sum_tmp_5611 = 0;
85 |
86 | /* 气压计温度原始数据 */
87 | ms5611_ut = (t_rxbuf[0] << 16) | (t_rxbuf[1] << 8) | t_rxbuf[2];
88 | /* 气压计压强原始数据 */
89 | ms5611_up = (p_rxbuf[0] << 16) | (p_rxbuf[1] << 8) | p_rxbuf[2];
90 | /* 气压计原始数据 */
91 | dT = ms5611_ut - ((uint32_t)ms5611_prom8[5] << 8);
92 | off = ((uint32_t)ms5611_prom8[2] << 16) + (((int64_t)dT * ms5611_prom8[4]) >> 7);
93 | sens = ((uint32_t)ms5611_prom8[1] << 15) + (((int64_t)dT * ms5611_prom8[3]) >> 8);
94 | temperature = 2000 + (((int64_t)dT * ms5611_prom8[6]) >> 23);
95 |
96 | /* 低于20摄氏度补偿 */
97 | if (temperature < 2000)
98 | {
99 | delt = temperature - 2000;
100 | delt = delt * delt;
101 | off2 = (5 * delt) >> 1;
102 | sens2 = (5 * delt) >> 2;
103 | /* 低于-15摄氏度补偿 */
104 | if (temperature < -1500)
105 | {
106 | delt = temperature + 1500;
107 | delt = delt * delt;
108 | off2 += 7 * delt;
109 | sens2 += (11 * delt) >> 1;
110 | }
111 | off -= off2;
112 | sens -= sens2;
113 | }
114 |
115 | /* 计算出气压并转换为高度 */
116 | pressure = (((ms5611_up * sens ) >> 21) - off) >> 15;
117 | alt_3 = (101000 - pressure)/1000.0f;
118 | pressure = 0.0082f *alt_3 * alt_3 *alt_3 + 0.09f *(101000 - pressure)*100.0f ;
119 | /* 气压计计算高度,单位mm(毫米) */
120 | baroAlt = pressure - baro_Offset;
121 | /* 气压计计算速度单位mm/s */
122 | baro_alt_speed += 5 *0.02 *3.14 *( 50 *( baroAlt - baroAltOld ) - baro_alt_speed );
123 | /* 保存数据下次使用 */
124 | baroAltOld = baroAlt;
125 |
126 | /* 第0-99次数据无效,用时20ms*100=2s */
127 | if( baro_start < 100 )
128 | {
129 | /* 计数次数增加 */
130 | baro_start++;
131 | /* 气压计计算速度 清零 */
132 | baro_alt_speed = 0;
133 | /* 气压计计算高度 清零 */
134 | baroAlt = 0;
135 | }
136 |
137 | /* 气压计温度积分滤波 */
138 | temperature_5611 += 0.01f *( ( 0.01f *temperature ) - temperature_5611 );
139 | }
140 |
141 | /*----------------------------------------------------------
142 | + 实现功能:气压计初始化
143 | ----------------------------------------------------------*/
144 | /* 气压计硬件故障 */
145 | u8 hard_error_ms5611;
146 | void MS5611_Init(void)
147 | {
148 | /* IIC延时等待 */
149 | Delay_ms(10);
150 | /* 气压计复位 */
151 | MS5611_Reset();
152 | /* IIC延时等待 */
153 | Delay_ms(3);
154 | /* 读取气压计PORM存储器 并判断硬件故障 */
155 | hard_error_ms5611 = MS5611_Read_Prom(ms5611_prom8);
156 | /* 开始读取温度 */
157 | MS5611_Start_T();
158 | }
159 |
160 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_ms5611.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 气压计驱动头文件
7 | *@design 无人机研究小组
8 | 谭政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _DRIVER_MS5611_H
16 | #define _DRIVER_MS5611_H
17 |
18 | #include "stm32f4xx.h"
19 | #include "device_iic.h"
20 | #include "device_ms5611.h"
21 | #include "driver_mpu6050.h"
22 | #include "database.h"
23 |
24 | /* 气压计硬件故障 */
25 | extern u8 hard_error_ms5611;
26 | /* 气压计计算高度,单位mm(毫米) */
27 | extern int32_t baroAlt,baroAltOld;
28 | /* 气压计计算速度单位mm/s */
29 | extern float baro_alt_speed;
30 |
31 | /*----------------------------------------------------------
32 | + 实现功能:气压计初始化
33 | ----------------------------------------------------------*/
34 | extern void MS5611_Init(void);
35 | /*----------------------------------------------------------
36 | + 实现功能:气压计数据更新 由任务调度调用周期10ms
37 | ----------------------------------------------------------*/
38 | extern int MS5611_Update(void);
39 | /*----------------------------------------------------------
40 | + 实现功能:气压计高度计算
41 | ----------------------------------------------------------*/
42 | extern void MS5611_BaroAltCalculate(void);
43 |
44 | #endif
45 |
46 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_parameter.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 默认参数及校准数据文件头文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _DRIVER_PARAMETER_H
16 | #define _DRIVER_PARAMETER_H
17 |
18 | #include "stm32f4xx.h"
19 | #include "database.h"
20 |
21 | /* PID参数数组 */
22 | extern pid_setup_t pid_setup;
23 |
24 | /*----------------------------------------------------------
25 | + 实现功能:PID参数恢复默认
26 | ----------------------------------------------------------*/
27 | extern void Para_ResetToFactorySetup(void);
28 |
29 | /*----------------------------------------------------------
30 | + 实现功能:所有参数初始化
31 | ----------------------------------------------------------*/
32 | extern void Para_Init(void);
33 |
34 | /*----------------------------------------------------------
35 | + 实现功能:保存加速度计的校准参数
36 | ----------------------------------------------------------*/
37 | extern void Param_SaveAccelOffset(xyz_f_t *offset);
38 |
39 | /*----------------------------------------------------------
40 | + 实现功能:保存陀螺仪的校准参数
41 | ----------------------------------------------------------*/
42 | extern void Param_SaveGyroOffset(xyz_f_t *offset);
43 |
44 | /*----------------------------------------------------------
45 | + 实现功能:保存磁力计的校准参数
46 | ----------------------------------------------------------*/
47 | extern void Param_SaveMagOffset(xyz_f_t *offset);
48 |
49 | /*----------------------------------------------------------
50 | + 实现功能:由任务调度调用周期20ms
51 | ----------------------------------------------------------*/
52 | extern void Parameter_Save(void);
53 |
54 | /*----------------------------------------------------------
55 | + 实现功能:所有参数初始化
56 | ----------------------------------------------------------*/
57 | extern void PID_Para_Init(void);
58 |
59 | #endif
60 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_power.c:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file driver_power.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 电池电压检测控制文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #include "stm32f4xx.h"
16 | #include "driver_power.h"
17 | #include "device_power.h"
18 |
19 | /* 滑动窗口滤波数值个数 */
20 | #define POWER_FILTER_NUM 10
21 |
22 | /* 滤波滑动窗口数组 */
23 | float POWER_FILT_BUF[(POWER_FILTER_NUM + 1)];
24 |
25 | /* 滤波滑动窗口数组下标 */
26 | uint8_t power_filter_cnt = 0,power_filter_cnt_old = 0;
27 | /* 电池电压 */
28 | uint16_t Electric_quantity = 0;
29 | /* 低电压模式 */
30 | uint8_t LowPower_Flag = 0;
31 |
32 |
33 | void Call_POWER_duty()
34 | {
35 | float temp = 0;
36 | float POWER_FILT_TMP = 0;
37 | /* 连续低电压计数 */
38 | static uint8_t lowpowercnt = 0;
39 |
40 | temp = Call_POWER_show();
41 | temp = temp * ( 1260.0f / (12.6f/23.3f*4096) );
42 |
43 | /* 滑动窗口滤波数组下标移位 */
44 | if( ++power_filter_cnt > POWER_FILTER_NUM )
45 | {
46 | power_filter_cnt = 0;
47 | power_filter_cnt_old = 1;
48 | }
49 | else
50 | power_filter_cnt_old = (power_filter_cnt == POWER_FILTER_NUM)? 0 : (power_filter_cnt + 1);
51 |
52 | /* 更新滤波滑动窗口临时数组 */
53 | POWER_FILT_BUF[power_filter_cnt] = temp;
54 |
55 | /* 更新滤波滑动窗口数组 */
56 | for(u8 i=0; iCCR4 = ( pwm_tem[CH_out_Mapping[0]] ) * PWM_RADIO + INIT_DUTY; //pwmout1
59 | TIM1->CCR3 = ( pwm_tem[CH_out_Mapping[1]] ) * PWM_RADIO + INIT_DUTY; //pwmout2
60 | TIM1->CCR2 = ( pwm_tem[CH_out_Mapping[2]] ) * PWM_RADIO + INIT_DUTY; //pwmout3
61 | TIM1->CCR1 = ( pwm_tem[CH_out_Mapping[3]] ) * PWM_RADIO + INIT_DUTY; //pwmout4
62 | TIM5->CCR4 = ( pwm_tem[CH_out_Mapping[4]] ) * PWM_RADIO + INIT_DUTY; //pwmout5
63 | TIM5->CCR3 = ( pwm_tem[CH_out_Mapping[5]] ) * PWM_RADIO + INIT_DUTY; //pwmout6
64 | TIM8->CCR4 = ( pwm_tem[CH_out_Mapping[6]] ) * PWM_RADIO + INIT_DUTY; //pwmout7
65 | TIM8->CCR3 = ( pwm_tem[CH_out_Mapping[7]] ) * PWM_RADIO + INIT_DUTY; //pwmout8
66 | }
67 |
68 | /* 输出PWM最小信号模式 */
69 | else if(PWM_Mode==1)
70 | {
71 | /* 配置数据按比例和起始值赋值寄存器 */
72 | TIM1->CCR4 = 0 * PWM_RADIO + INIT_DUTY; //pwmout1
73 | TIM1->CCR3 = 0 * PWM_RADIO + INIT_DUTY; //pwmout2
74 | TIM1->CCR2 = 0 * PWM_RADIO + INIT_DUTY; //pwmout3
75 | TIM1->CCR1 = 0 * PWM_RADIO + INIT_DUTY; //pwmout4
76 | TIM5->CCR4 = 0 * PWM_RADIO + INIT_DUTY; //pwmout5
77 | TIM5->CCR3 = 0 * PWM_RADIO + INIT_DUTY; //pwmout6
78 | TIM8->CCR4 = 0 * PWM_RADIO + INIT_DUTY; //pwmout7
79 | TIM8->CCR3 = 0 * PWM_RADIO + INIT_DUTY; //pwmout8
80 | }
81 |
82 | /* 输出PWM最大信号模式 */
83 | else if(PWM_Mode==2)
84 | {
85 | /* 配置数据按比例和起始值赋值寄存器 */
86 | TIM1->CCR4 = 1000 * PWM_RADIO + INIT_DUTY; //pwmout1
87 | TIM1->CCR3 = 1000 * PWM_RADIO + INIT_DUTY; //pwmout2
88 | TIM1->CCR2 = 1000 * PWM_RADIO + INIT_DUTY; //pwmout3
89 | TIM1->CCR1 = 1000 * PWM_RADIO + INIT_DUTY; //pwmout4
90 | TIM5->CCR4 = 1000 * PWM_RADIO + INIT_DUTY; //pwmout5
91 | TIM5->CCR3 = 1000 * PWM_RADIO + INIT_DUTY; //pwmout6
92 | TIM8->CCR4 = 1000 * PWM_RADIO + INIT_DUTY; //pwmout7
93 | TIM8->CCR3 = 1000 * PWM_RADIO + INIT_DUTY; //pwmout8
94 | }
95 | }
96 |
97 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_pwm_out.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief PWM输出设备头文件
7 | *@design 无人机研究小组
8 | 谭政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _DRIVER_PWM_OUT_H_
16 | #define _DRIVER_PWM_OUT_H_
17 |
18 | #include "stm32f4xx.h"
19 | #include "device_pwm_out.h"
20 |
21 | /* PWM的8个通道输出模式 */
22 | extern int PWM_Mode;
23 |
24 | /*----------------------------------------------------------
25 | + 实现功能:PWM的8个通道输出数据的调用
26 | + 调用参数功能:双字节整数数组:设置的数据(0-1000)
27 | ----------------------------------------------------------*/
28 | extern void SetPwm(int16_t set_8pwm[]);
29 |
30 | #endif
31 |
32 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_ultrasonic.c:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file driver_ultrasonic.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 超声波测距驱动文件
7 | *@design 无人机研究小组
8 | 谈政政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #include "stm32f4xx.h"
16 | #include "driver_ultrasonic.h"
17 | #include "driver_usart.h"
18 | #include "database.h"
19 |
20 | /* 超声波模块型号选择宏定义,可选US100型号或者KS103 */
21 | #define USE_US100 //#define USE_KS103
22 |
23 | /* 超声波模块状态标志位:1准备接收高位 2准备接受低位 */
24 | s8 ultra_state;
25 | /* 检测是否连接超声波模块 */
26 | u8 ultra_ok = 0;
27 | /* 超声波模块测量距离:单位毫米 */
28 | u16 ultra_distance,ultra_distance_old;
29 | /* 超声波模块测量距离两次差:单位毫米 */
30 | s16 ultra_delta;
31 |
32 | /*----------------------------------------------------------
33 | + 实现功能:超声波模块初始化
34 | ----------------------------------------------------------*/
35 | void Ultrasonic_Init()
36 | {
37 | /* 串口5初始化,波特率9600 */
38 | Device_Usart5_ENABLE_Init(9600,2,1,DISABLE,ENABLE);
39 | }
40 |
41 | /*----------------------------------------------------------
42 | + 实现功能:由任务调度调用周期100ms
43 | ----------------------------------------------------------*/
44 | void Call_Ultrasonic()
45 | {
46 | /* 选择了KS103超声波模块 */
47 | #if defined(USE_KS103)
48 | /* KS103超声波模块默认配置数据 */
49 | u8 temp[3] = {0xe8,0x02,0xbc};
50 | /* 发送配置数据 */
51 | Uart5_Send(temp ,3);
52 |
53 | /* 选择了US100超声波模块 */
54 | #elif defined(USE_US100)
55 | /* US100超声波模块默认配置数据 */
56 | u8 temp = 0x55;
57 | /* 发送配置数据 */
58 | Uart5_Send(&temp ,1);
59 |
60 | /* 结束选择模块宏定义 */
61 | #endif
62 |
63 | /* 开始接收高位数据 */
64 | ultra_state = 1;
65 | }
66 |
67 | /*----------------------------------------------------------
68 | + 实现功能:串口5接收到数据解析
69 | + 调用参数功能:单字节整数:串口接收到的数据
70 | ----------------------------------------------------------*/
71 | void Ultra_Get(u8 com_data)
72 | {
73 | /* 接收数据暂存 */
74 | static u8 ultra_tmp;
75 |
76 | /*判断是高位数据*/
77 | if( ultra_state == 1 )
78 | {
79 | /* 记录下数据 */
80 | ultra_tmp = com_data;
81 | /* 下次判断低位数据 */
82 | ultra_state = 2;
83 | }
84 |
85 | /*判断是低位数据*/
86 | else if( ultra_state == 2 )
87 | {
88 | /* 接收测量数据,单位毫米 */
89 | ultra_distance = (ultra_tmp<<8) + com_data;
90 | /* 置为状态位 */
91 | ultra_state = 0;
92 | /* 正确获取了数据 */
93 | ultra_ok = 1;
94 | }
95 |
96 | /* 最近两次测距差 */
97 | ultra_delta = ultra_distance - ultra_distance_old;
98 | /* 存储测距数据 */
99 | ultra_distance_old = ultra_distance;
100 | }
101 |
102 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_ultrasonic.h:
--------------------------------------------------------------------------------
1 | /*
2 | *---------------基于"HAL底层库"的工程(CAUC_Flight)--------------
3 | *@file main.c
4 | *@version V1.0
5 | *@date 2018/5/24
6 | *@brief 超声波测距驱动头文件
7 | *@design 无人机研究小组
8 | 谭政 朱通 赵志华 邓丽萍 张硕
9 | *
10 | *@all copyright reserved 中国民航大学 机器人研究所
11 | *@hardware platform STM32F40X
12 | *@remark We are a team.
13 | *@motto I just want to know why the BeiJing MTR Line 4 are so many people every day.
14 | */
15 | #ifndef _DRIVER_ULTRASONIC_H
16 | #define _DRIVER_ULTRASONIC_H
17 |
18 | #include "stm32f4xx.h"
19 | #include "database.h"
20 |
21 | /* 超声波模块状态标志位:1准备接收高位 2准备接受低位 */
22 | extern s8 ultra_state;
23 | /* 超声波模块测量距离:单位毫米 */
24 | extern u16 ultra_distance;
25 | /* 超声波模块测量距离两次差:单位毫米 */
26 | extern s16 ultra_delta;
27 |
28 | /*----------------------------------------------------------
29 | + 实现功能:超声波模块初始化
30 | ----------------------------------------------------------*/
31 | void Ultrasonic_Init(void);
32 |
33 | /*----------------------------------------------------------
34 | + 实现功能:由任务调度调用周期100ms
35 | ----------------------------------------------------------*/
36 | void Call_Ultrasonic(void);
37 |
38 | /*----------------------------------------------------------
39 | + 实现功能:串口5接收到数据解析
40 | + 调用参数功能:单字节整数:串口接收到的数据
41 | ----------------------------------------------------------*/
42 | void Ultra_Get(u8 com_data);
43 |
44 | #endif
45 |
46 |
--------------------------------------------------------------------------------
/CAUC-Flight/drivers/driver_usart.h:
--------------------------------------------------------------------------------
1 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved.
2 | + 文件名 :driver_usart.h
3 | + 描述 :串口驱动头文件
4 | 代码尽量做到逐行注释 代码有问题,及时加群交流 作者有偿支持对开源代码的完善 */
5 | #ifndef _DRIVER_USART_H
6 | #define _DRIVER_USART_H
7 |
8 | #include "stm32f4xx.h"
9 | #include "device_usart.h"
10 |
11 | /*----------------------------------------------------------
12 | + 实现功能:串口2发送数据调用
13 | + 调用参数功能:字符串数组:发送数据,单字节整数:数据长度
14 | ----------------------------------------------------------*/
15 | extern void Usart2_Send(unsigned char *DataToSend ,u8 data_num);
16 |
17 | /*----------------------------------------------------------
18 | + 实现功能:串口4发送数据调用
19 | + 调用参数功能:字符串数组:发送数据,单字节整数:数据长度
20 | ----------------------------------------------------------*/
21 | extern void Uart4_Send(unsigned char *DataToSend ,u8 data_num);
22 |
23 | /*----------------------------------------------------------
24 | + 实现功能:串口5发送数据调用
25 | + 调用参数功能:字符串数组:发送数据,单字节整数:数据长度
26 | ----------------------------------------------------------*/
27 | extern void Uart5_Send(unsigned char *DataToSend ,u8 data_num);
28 |
29 | #endif
30 | /* ©2015-2016 Beijing Bechade Opto-Electronic, Co.,Ltd. All rights reserved. */
31 |
--------------------------------------------------------------------------------
/CMSIS/arm_cortexM4lf_math.lib:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/zhangdashuo/CAUC_Flight/dc2cf767939d95d29d464dac213ef2f41daab39f/CMSIS/arm_cortexM4lf_math.lib
--------------------------------------------------------------------------------
/CMSIS/version.c:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #include "string.h"
17 | #include "version.h"
18 |
19 |
20 | extern uint8_t BlockBuf[];
21 |
22 | // Pointers to substitution strings
23 | const char *fw_version = (const char *)FW_BUILD;
24 |
25 |
26 | uint8_t string_auth[25 + 4];
27 | uint8_t string_auth_descriptor[2+25*2];
28 |
29 |
30 | uint8_t get_len_string_interface(void) {
31 | return 2 + strlen((const char *)(string_auth+4))*2;
32 | }
33 |
34 | uint8_t * get_uid_string_interface(void) {
35 | return string_auth_descriptor;
36 | }
37 |
38 | const uint8_t board_secret[9] = "k4flu5fs";
39 |
--------------------------------------------------------------------------------
/CMSIS/version.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef VERSION_H
17 | #define VERSION_H
18 |
19 | #include "stdint.h"
20 |
21 | #define FW_BUILD "0202"
22 |
23 | uint8_t update_html_file(void);
24 | uint8_t get_len_string_interface(void);
25 | uint8_t *get_uid_string_interface(void);
26 |
27 | #endif
28 |
--------------------------------------------------------------------------------
/DebugConfig/APP_STM32F407VGTx.dbgconf:
--------------------------------------------------------------------------------
1 | // <<< Use Configuration Wizard in Context Menu >>>
2 |
3 | // Debug MCU Configuration
4 | // DBG_SLEEP Debug Sleep Mode
5 | // DBG_STOP Debug Stop Mode
6 | // DBG_STANDBY Debug Standby Mode
7 | //
8 | DbgMCU_CR = 0x00000007;
9 |
10 | // Debug MCU APB1 Freeze
11 | // DBG_TIM2_STOP Timer 2 Stopped when Core is halted
12 | // DBG_TIM3_STOP Timer 3 Stopped when Core is halted
13 | // DBG_TIM4_STOP Timer 4 Stopped when Core is halted
14 | // DBG_TIM5_STOP Timer 5 Stopped when Core is halted
15 | // DBG_TIM6_STOP Timer 6 Stopped when Core is halted
16 | // DBG_TIM7_STOP Timer 7 Stopped when Core is halted
17 | // DBG_TIM12_STOP Timer 12 Stopped when Core is halted
18 | // DBG_TIM13_STOP Timer 13 Stopped when Core is halted
19 | // DBG_TIM14_STOP Timer 14 Stopped when Core is halted
20 | // DBG_RTC_STOP RTC Stopped when Core is halted
21 | // DBG_WWDG_STOP Window Watchdog Stopped when Core is halted
22 | // DBG_IWDG_STOP Independent Watchdog Stopped when Core is halted
23 | // DBG_I2C1_SMBUS_TIMEOUT I2C1 SMBUS Timeout Mode Stopped when Core is halted
24 | // DBG_I2C2_SMBUS_TIMEOUT I2C2 SMBUS Timeout Mode Stopped when Core is halted
25 | // DBG_I2C3_SMBUS_TIMEOUT I2C3 SMBUS Timeout Mode Stopped when Core is halted
26 | // DBG_CAN1_STOP CAN1 Stopped when Core is halted
27 | // DBG_CAN2_STOP CAN2 Stopped when Core is halted
28 | //
29 | DbgMCU_APB1_Fz = 0x00000000;
30 |
31 |
32 | // Debug MCU APB2 Freeze
33 | // DBG_TIM1_STOP Timer 1 Stopped when Core is halted
34 | // DBG_TIM8_STOP Timer 8 Stopped when Core is halted
35 | // DBG_TIM9_STOP Timer 9 Stopped when Core is halted
36 | // DBG_TIM10_STOP Timer 10 Stopped when Core is halted
37 | // DBG_TIM11_STOP Timer 11 Stopped when Core is halted
38 | //
39 | DbgMCU_APB2_Fz = 0x00000000;
40 |
41 | // <<< end of configuration section >>>
--------------------------------------------------------------------------------
/DebugConfig/CAUC-Flight_STM32F407VGTx.dbgconf:
--------------------------------------------------------------------------------
1 | // <<< Use Configuration Wizard in Context Menu >>>
2 |
3 | // Debug MCU Configuration
4 | // DBG_SLEEP Debug Sleep Mode
5 | // DBG_STOP Debug Stop Mode
6 | // DBG_STANDBY Debug Standby Mode
7 | //
8 | DbgMCU_CR = 0x00000007;
9 |
10 | // Debug MCU APB1 Freeze
11 | // DBG_TIM2_STOP Timer 2 Stopped when Core is halted
12 | // DBG_TIM3_STOP Timer 3 Stopped when Core is halted
13 | // DBG_TIM4_STOP Timer 4 Stopped when Core is halted
14 | // DBG_TIM5_STOP Timer 5 Stopped when Core is halted
15 | // DBG_TIM6_STOP Timer 6 Stopped when Core is halted
16 | // DBG_TIM7_STOP Timer 7 Stopped when Core is halted
17 | // DBG_TIM12_STOP Timer 12 Stopped when Core is halted
18 | // DBG_TIM13_STOP Timer 13 Stopped when Core is halted
19 | // DBG_TIM14_STOP Timer 14 Stopped when Core is halted
20 | // DBG_RTC_STOP RTC Stopped when Core is halted
21 | // DBG_WWDG_STOP Window Watchdog Stopped when Core is halted
22 | // DBG_IWDG_STOP Independent Watchdog Stopped when Core is halted
23 | // DBG_I2C1_SMBUS_TIMEOUT I2C1 SMBUS Timeout Mode Stopped when Core is halted
24 | // DBG_I2C2_SMBUS_TIMEOUT I2C2 SMBUS Timeout Mode Stopped when Core is halted
25 | // DBG_I2C3_SMBUS_TIMEOUT I2C3 SMBUS Timeout Mode Stopped when Core is halted
26 | // DBG_CAN1_STOP CAN1 Stopped when Core is halted
27 | // DBG_CAN2_STOP CAN2 Stopped when Core is halted
28 | //
29 | DbgMCU_APB1_Fz = 0x00000000;
30 |
31 |
32 | // Debug MCU APB2 Freeze
33 | // DBG_TIM1_STOP Timer 1 Stopped when Core is halted
34 | // DBG_TIM8_STOP Timer 8 Stopped when Core is halted
35 | // DBG_TIM9_STOP Timer 9 Stopped when Core is halted
36 | // DBG_TIM10_STOP Timer 10 Stopped when Core is halted
37 | // DBG_TIM11_STOP Timer 11 Stopped when Core is halted
38 | //
39 | DbgMCU_APB2_Fz = 0x00000000;
40 |
41 | // <<< end of configuration section >>>
--------------------------------------------------------------------------------
/DebugConfig/Target_1_STM32F407VGTx.dbgconf:
--------------------------------------------------------------------------------
1 | // <<< Use Configuration Wizard in Context Menu >>>
2 |
3 | // Debug MCU Configuration
4 | // DBG_SLEEP Debug Sleep Mode
5 | // DBG_STOP Debug Stop Mode
6 | // DBG_STANDBY Debug Standby Mode
7 | //
8 | DbgMCU_CR = 0x00000007;
9 |
10 | // Debug MCU APB1 Freeze
11 | // DBG_TIM2_STOP Timer 2 Stopped when Core is halted
12 | // DBG_TIM3_STOP Timer 3 Stopped when Core is halted
13 | // DBG_TIM4_STOP Timer 4 Stopped when Core is halted
14 | // DBG_TIM5_STOP Timer 5 Stopped when Core is halted
15 | // DBG_TIM6_STOP Timer 6 Stopped when Core is halted
16 | // DBG_TIM7_STOP Timer 7 Stopped when Core is halted
17 | // DBG_TIM12_STOP Timer 12 Stopped when Core is halted
18 | // DBG_TIM13_STOP Timer 13 Stopped when Core is halted
19 | // DBG_TIM14_STOP Timer 14 Stopped when Core is halted
20 | // DBG_RTC_STOP RTC Stopped when Core is halted
21 | // DBG_WWDG_STOP Window Watchdog Stopped when Core is halted
22 | // DBG_IWDG_STOP Independent Watchdog Stopped when Core is halted
23 | // DBG_I2C1_SMBUS_TIMEOUT I2C1 SMBUS Timeout Mode Stopped when Core is halted
24 | // DBG_I2C2_SMBUS_TIMEOUT I2C2 SMBUS Timeout Mode Stopped when Core is halted
25 | // DBG_I2C3_SMBUS_TIMEOUT I2C3 SMBUS Timeout Mode Stopped when Core is halted
26 | // DBG_CAN1_STOP CAN1 Stopped when Core is halted
27 | // DBG_CAN2_STOP CAN2 Stopped when Core is halted
28 | //
29 | DbgMCU_APB1_Fz = 0x00000000;
30 |
31 |
32 | // Debug MCU APB2 Freeze
33 | // DBG_TIM1_STOP Timer 1 Stopped when Core is halted
34 | // DBG_TIM8_STOP Timer 8 Stopped when Core is halted
35 | // DBG_TIM9_STOP Timer 9 Stopped when Core is halted
36 | // DBG_TIM10_STOP Timer 10 Stopped when Core is halted
37 | // DBG_TIM11_STOP Timer 11 Stopped when Core is halted
38 | //
39 | DbgMCU_APB2_Fz = 0x00000000;
40 |
41 | // <<< end of configuration section >>>
--------------------------------------------------------------------------------
/DebugConfig/applications_STM32F407VGTx.dbgconf:
--------------------------------------------------------------------------------
1 | // <<< Use Configuration Wizard in Context Menu >>>
2 |
3 | // Debug MCU Configuration
4 | // DBG_SLEEP Debug Sleep Mode
5 | // DBG_STOP Debug Stop Mode
6 | // DBG_STANDBY Debug Standby Mode
7 | //
8 | DbgMCU_CR = 0x00000007;
9 |
10 | // Debug MCU APB1 Freeze
11 | // DBG_TIM2_STOP Timer 2 Stopped when Core is halted
12 | // DBG_TIM3_STOP Timer 3 Stopped when Core is halted
13 | // DBG_TIM4_STOP Timer 4 Stopped when Core is halted
14 | // DBG_TIM5_STOP Timer 5 Stopped when Core is halted
15 | // DBG_TIM6_STOP Timer 6 Stopped when Core is halted
16 | // DBG_TIM7_STOP Timer 7 Stopped when Core is halted
17 | // DBG_TIM12_STOP Timer 12 Stopped when Core is halted
18 | // DBG_TIM13_STOP Timer 13 Stopped when Core is halted
19 | // DBG_TIM14_STOP Timer 14 Stopped when Core is halted
20 | // DBG_RTC_STOP RTC Stopped when Core is halted
21 | // DBG_WWDG_STOP Window Watchdog Stopped when Core is halted
22 | // DBG_IWDG_STOP Independent Watchdog Stopped when Core is halted
23 | // DBG_I2C1_SMBUS_TIMEOUT I2C1 SMBUS Timeout Mode Stopped when Core is halted
24 | // DBG_I2C2_SMBUS_TIMEOUT I2C2 SMBUS Timeout Mode Stopped when Core is halted
25 | // DBG_I2C3_SMBUS_TIMEOUT I2C3 SMBUS Timeout Mode Stopped when Core is halted
26 | // DBG_CAN1_STOP CAN1 Stopped when Core is halted
27 | // DBG_CAN2_STOP CAN2 Stopped when Core is halted
28 | //
29 | DbgMCU_APB1_Fz = 0x00000000;
30 |
31 |
32 | // Debug MCU APB2 Freeze
33 | // DBG_TIM1_STOP Timer 1 Stopped when Core is halted
34 | // DBG_TIM8_STOP Timer 8 Stopped when Core is halted
35 | // DBG_TIM9_STOP Timer 9 Stopped when Core is halted
36 | // DBG_TIM10_STOP Timer 10 Stopped when Core is halted
37 | // DBG_TIM11_STOP Timer 11 Stopped when Core is halted
38 | //
39 | DbgMCU_APB2_Fz = 0x00000000;
40 |
41 | // <<< end of configuration section >>>
--------------------------------------------------------------------------------
/JLinkLog.txt:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/zhangdashuo/CAUC_Flight/dc2cf767939d95d29d464dac213ef2f41daab39f/JLinkLog.txt
--------------------------------------------------------------------------------
/JLinkSettings.ini:
--------------------------------------------------------------------------------
1 | [BREAKPOINTS]
2 | ShowInfoWin = 1
3 | EnableFlashBP = 2
4 | BPDuringExecution = 0
5 | ForceImpTypeAny = 0
6 | [CFI]
7 | CFISize = 0x00
8 | CFIAddr = 0x00
9 | [CPU]
10 | OverrideMemMap = 0
11 | AllowSimulation = 1
12 | ScriptFile=""
13 | LowPowerHandlingMode = 0
14 | [FLASH]
15 | CacheExcludeSize = 0x00
16 | CacheExcludeAddr = 0x00
17 | MinNumBytesFlashDL = 0
18 | SkipProgOnCRCMatch = 1
19 | VerifyDownload = 1
20 | AllowCaching = 1
21 | EnableFlashDL = 2
22 | Override = 1
23 | Device="Unspecified"
24 | [GENERAL]
25 | WorkRAMSize = 0x00
26 | WorkRAMAddr = 0x00
27 | RAMUsageLimit = 0x00
28 | [SWO]
29 | SWOLogFile=""
30 | [MEM]
31 | RdOverrideOrMask = 0x00
32 | RdOverrideAndMask = 0xFFFFFFFF
33 | RdOverrideAddr = 0xFFFFFFFF
34 | WrOverrideOrMask = 0x00
35 | WrOverrideAndMask = 0xFFFFFFFF
36 | WrOverrideAddr = 0xFFFFFFFF
37 |
--------------------------------------------------------------------------------
/Objects/CAUC-Flight.build_log.htm:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/zhangdashuo/CAUC_Flight/dc2cf767939d95d29d464dac213ef2f41daab39f/Objects/CAUC-Flight.build_log.htm
--------------------------------------------------------------------------------
/Objects/CAUC-Flight.lnp:
--------------------------------------------------------------------------------
1 | --cpu Cortex-M4.fp
2 | ".\objects\misc.o"
3 | ".\objects\stm32f4xx_adc.o"
4 | ".\objects\stm32f4xx_can.o"
5 | ".\objects\stm32f4xx_crc.o"
6 | ".\objects\stm32f4xx_cryp.o"
7 | ".\objects\stm32f4xx_cryp_aes.o"
8 | ".\objects\stm32f4xx_cryp_des.o"
9 | ".\objects\stm32f4xx_cryp_tdes.o"
10 | ".\objects\stm32f4xx_dac.o"
11 | ".\objects\stm32f4xx_dbgmcu.o"
12 | ".\objects\stm32f4xx_dcmi.o"
13 | ".\objects\stm32f4xx_dma.o"
14 | ".\objects\stm32f4xx_dma2d.o"
15 | ".\objects\stm32f4xx_exti.o"
16 | ".\objects\stm32f4xx_flash.o"
17 | ".\objects\stm32f4xx_fmc.o"
18 | ".\objects\stm32f4xx_fsmc.o"
19 | ".\objects\stm32f4xx_gpio.o"
20 | ".\objects\stm32f4xx_hash.o"
21 | ".\objects\stm32f4xx_hash_md5.o"
22 | ".\objects\stm32f4xx_hash_sha1.o"
23 | ".\objects\stm32f4xx_i2c.o"
24 | ".\objects\stm32f4xx_iwdg.o"
25 | ".\objects\stm32f4xx_ltdc.o"
26 | ".\objects\stm32f4xx_pwr.o"
27 | ".\objects\stm32f4xx_rcc.o"
28 | ".\objects\stm32f4xx_rng.o"
29 | ".\objects\stm32f4xx_rtc.o"
30 | ".\objects\stm32f4xx_sai.o"
31 | ".\objects\stm32f4xx_sdio.o"
32 | ".\objects\stm32f4xx_spi.o"
33 | ".\objects\stm32f4xx_syscfg.o"
34 | ".\objects\stm32f4xx_tim.o"
35 | ".\objects\stm32f4xx_usart.o"
36 | ".\objects\stm32f4xx_wwdg.o"
37 | ".\objects\main.o"
38 | ".\objects\device_ak8975.o"
39 | ".\objects\device_fatfs.o"
40 | ".\objects\device_iic.o"
41 | ".\objects\device_led.o"
42 | ".\objects\device_mpu6050.o"
43 | ".\objects\device_ms5611.o"
44 | ".\objects\device_pwm_in.o"
45 | ".\objects\device_pwm_out.o"
46 | ".\objects\device_timer.o"
47 | ".\objects\device_usart.o"
48 | ".\objects\device_w25qxx.o"
49 | ".\objects\usb_config.o"
50 | ".\objects\usbd_user_hid.o"
51 | ".\objects\usbd_stm32f4xx_fs.o"
52 | ".\objects\device_beep.o"
53 | ".\objects\device_power.o"
54 | ".\objects\ctrl.o"
55 | ".\objects\data_transfer.o"
56 | ".\objects\filter.o"
57 | ".\objects\height_ctrl.o"
58 | ".\objects\imu.o"
59 | ".\objects\init.o"
60 | ".\objects\mymath.o"
61 | ".\objects\optical_flow.o"
62 | ".\objects\position_control.o"
63 | ".\objects\rc.o"
64 | ".\objects\scheduler.o"
65 | ".\objects\time.o"
66 | ".\objects\ofposition_control.o"
67 | ".\objects\driver_ak8975.o"
68 | ".\objects\driver_disk.o"
69 | ".\objects\driver_gps.o"
70 | ".\objects\driver_led.o"
71 | ".\objects\driver_mpu6050.o"
72 | ".\objects\driver_ms5611.o"
73 | ".\objects\driver_parameter.o"
74 | ".\objects\driver_pwm_in.o"
75 | ".\objects\driver_pwm_out.o"
76 | ".\objects\driver_ultrasonic.o"
77 | ".\objects\driver_usart.o"
78 | ".\objects\driver_beep.o"
79 | ".\objects\driver_power.o"
80 | ".\objects\driver_lidarlite.o"
81 | ".\objects\startup_stm32f40_41xxx.o"
82 | ".\objects\stm32f4xx_it.o"
83 | ".\objects\system_stm32f4xx.o"
84 | ".\CMSIS\arm_cortexM4lf_math.lib"
85 | ".\objects\version.o"
86 | ".\objects\usbd_core.o"
87 | ".\objects\usbd_core_hid.o"
88 | ".\objects\usbd_hid.o"
89 | --library_type=microlib --strict --scatter ".\Objects\CAUC-Flight.sct"
90 | --summary_stderr --info summarysizes --map --xref --callgraph --symbols
91 | --info sizes --info totals --info unused --info veneers
92 | --list ".\Listings\CAUC-Flight.map" -o .\Objects\CAUC-Flight.axf
--------------------------------------------------------------------------------
/Objects/CAUC-Flight.sct:
--------------------------------------------------------------------------------
1 | ; *************************************************************
2 | ; *** Scatter-Loading Description File generated by uVision ***
3 | ; *************************************************************
4 |
5 | LR_IROM1 0x08000000 0x00100000 { ; load region size_region
6 | ER_IROM1 0x08000000 0x00100000 { ; load address = execution address
7 | *.o (RESET, +First)
8 | *(InRoot$$Sections)
9 | .ANY (+RO)
10 | }
11 | RW_IRAM1 0x20000000 0x00020000 { ; RW data
12 | .ANY (+RW +ZI)
13 | }
14 | }
15 |
16 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # CAUC_Flight
2 | 中国民航大学无人机研究小组研制,支持OpenMV光流,PIX光流,GPS定位,硬件平台STM32F407,开发环境Windows下keil
3 | ---
4 | 该软件是由中国民航大学机器人研究所无人机控制实验室由Light飞控代码(EMIDE)开发环境下移植到KEIL开发环境下,同时对该代码进行了大量的优化和功能上的增加。该代码的解释权由中国民航大学所有,禁止商业使用,同时如有使用请注明出处。
5 | ---
6 |
--------------------------------------------------------------------------------
/STM32F40X/stm32f4xx.h:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/zhangdashuo/CAUC_Flight/dc2cf767939d95d29d464dac213ef2f41daab39f/STM32F40X/stm32f4xx.h
--------------------------------------------------------------------------------
/STM32F40X/stm32f4xx_it.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file Project/STM32F4xx_StdPeriph_Templates/stm32f4xx_it.h
4 | * @author MCD Application Team
5 | * @version V1.4.0
6 | * @date 04-August-2014
7 | * @brief This file contains the headers of the interrupt handlers.
8 | ******************************************************************************
9 | * @attention
10 | *
11 | * © COPYRIGHT 2014 STMicroelectronics
12 | *
13 | * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
14 | * You may not use this file except in compliance with the License.
15 | * You may obtain a copy of the License at:
16 | *
17 | * http://www.st.com/software_license_agreement_liberty_v2
18 | *
19 | * Unless required by applicable law or agreed to in writing, software
20 | * distributed under the License is distributed on an "AS IS" BASIS,
21 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
22 | * See the License for the specific language governing permissions and
23 | * limitations under the License.
24 | *
25 | ******************************************************************************
26 | */
27 |
28 | /* Define to prevent recursive inclusion -------------------------------------*/
29 | #ifndef __STM32F4xx_IT_H
30 | #define __STM32F4xx_IT_H
31 |
32 | #ifdef __cplusplus
33 | extern "C" {
34 | #endif
35 |
36 | /* Includes ------------------------------------------------------------------*/
37 | #include "stm32f4xx.h"
38 |
39 | /* Exported types ------------------------------------------------------------*/
40 | /* Exported constants --------------------------------------------------------*/
41 | /* Exported macro ------------------------------------------------------------*/
42 | /* Exported functions ------------------------------------------------------- */
43 |
44 | void NMI_Handler(void);
45 | void HardFault_Handler(void);
46 | void MemManage_Handler(void);
47 | void BusFault_Handler(void);
48 | void UsageFault_Handler(void);
49 | void SVC_Handler(void);
50 | void DebugMon_Handler(void);
51 | void PendSV_Handler(void);
52 | void SysTick_Handler(void);
53 |
54 | #ifdef __cplusplus
55 | }
56 | #endif
57 |
58 | #endif /* __STM32F4xx_IT_H */
59 |
60 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
61 |
--------------------------------------------------------------------------------
/STM32F40X/system_stm32f4xx.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file system_stm32f4xx.h
4 | * @author MCD Application Team
5 | * @version V1.4.0
6 | * @date 04-August-2014
7 | * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
8 | ******************************************************************************
9 | * @attention
10 | *
11 | * © COPYRIGHT 2014 STMicroelectronics
12 | *
13 | * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
14 | * You may not use this file except in compliance with the License.
15 | * You may obtain a copy of the License at:
16 | *
17 | * http://www.st.com/software_license_agreement_liberty_v2
18 | *
19 | * Unless required by applicable law or agreed to in writing, software
20 | * distributed under the License is distributed on an "AS IS" BASIS,
21 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
22 | * See the License for the specific language governing permissions and
23 | * limitations under the License.
24 | *
25 | ******************************************************************************
26 | */
27 |
28 | /** @addtogroup CMSIS
29 | * @{
30 | */
31 |
32 | /** @addtogroup stm32f4xx_system
33 | * @{
34 | */
35 |
36 | /**
37 | * @brief Define to prevent recursive inclusion
38 | */
39 | #ifndef __SYSTEM_STM32F4XX_H
40 | #define __SYSTEM_STM32F4XX_H
41 |
42 | #ifdef __cplusplus
43 | extern "C" {
44 | #endif
45 |
46 | /** @addtogroup STM32F4xx_System_Includes
47 | * @{
48 | */
49 |
50 | /**
51 | * @}
52 | */
53 |
54 |
55 | /** @addtogroup STM32F4xx_System_Exported_types
56 | * @{
57 | */
58 |
59 | extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
60 |
61 |
62 | /**
63 | * @}
64 | */
65 |
66 | /** @addtogroup STM32F4xx_System_Exported_Constants
67 | * @{
68 | */
69 |
70 | /**
71 | * @}
72 | */
73 |
74 | /** @addtogroup STM32F4xx_System_Exported_Macros
75 | * @{
76 | */
77 |
78 | /**
79 | * @}
80 | */
81 |
82 | /** @addtogroup STM32F4xx_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_STM32F4XX_H */
97 |
98 | /**
99 | * @}
100 | */
101 |
102 | /**
103 | * @}
104 | */
105 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
106 |
--------------------------------------------------------------------------------
/USBStack/INC/rl_usb.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __RL_USB_H__
17 | #define __RL_USB_H__
18 |
19 | #ifdef __cplusplus
20 | extern "C" {
21 | #endif
22 |
23 | #include "stdint.h"
24 | #include "usb.h"
25 |
26 | /***************** Functions *************************************************/
27 |
28 | /* USB Device functions exported from USB Device Core module */
29 | extern void usbd_init (void);
30 | extern void usbd_connect (BOOL con);
31 | extern void usbd_reset_core (void);
32 | extern BOOL usbd_configured (void);
33 |
34 | /* USB Device user functions imported to USB HID Class module */
35 | extern void usbd_hid_init (void);
36 | extern BOOL usbd_hid_get_report_trigger(U8 rid, U8 *buf, int len);
37 | extern int usbd_hid_get_report (U8 rtype, U8 rid, U8 *buf, U8 req);
38 | extern void usbd_hid_set_report (U8 rtype, U8 rid, U8 *buf, int len, U8 req);
39 | extern U8 usbd_hid_get_protocol (void);
40 | extern void usbd_hid_set_protocol (U8 protocol);
41 |
42 | /* USB Device user functions imported to USB Mass Storage Class module */
43 | extern void usbd_msc_init (void);
44 | extern void usbd_msc_read_sect (U32 block, U8 *buf, U32 num_of_blocks);
45 | extern void usbd_msc_write_sect (U32 block, U8 *buf, U32 num_of_blocks);
46 | extern void usbd_msc_start_stop (BOOL start);
47 |
48 | /* USB Device user functions imported to USB Audio Class module */
49 | extern void usbd_adc_init (void);
50 |
51 | /* USB Device CDC ACM class functions called automatically by USBD Core module*/
52 | extern int32_t USBD_CDC_ACM_Initialize (void);
53 | extern int32_t USBD_CDC_ACM_Uninitialize (void);
54 | extern int32_t USBD_CDC_ACM_Reset (void);
55 | /* USB Device CDC ACM class user functions */
56 | extern int32_t USBD_CDC_ACM_PortInitialize (void);
57 | extern int32_t USBD_CDC_ACM_PortUninitialize (void);
58 | extern int32_t USBD_CDC_ACM_PortReset (void);
59 | extern int32_t USBD_CDC_ACM_PortSetLineCoding (CDC_LINE_CODING *line_coding);
60 | extern int32_t USBD_CDC_ACM_PortGetLineCoding (CDC_LINE_CODING *line_coding);
61 | extern int32_t USBD_CDC_ACM_PortSetControlLineState (uint16_t ctrl_bmp);
62 | extern int32_t USBD_CDC_ACM_DataSend (const uint8_t *buf, int32_t len);
63 | extern int32_t USBD_CDC_ACM_DataFree (void);
64 | extern int32_t USBD_CDC_ACM_PutChar (const uint8_t ch);
65 | extern int32_t USBD_CDC_ACM_DataRead ( uint8_t *buf, int32_t len);
66 | extern int32_t USBD_CDC_ACM_GetChar (void);
67 | extern int32_t USBD_CDC_ACM_DataAvailable (void);
68 | extern int32_t USBD_CDC_ACM_Notify (uint16_t stat);
69 | /* USB Device CDC ACM class overridable functions */
70 | extern int32_t USBD_CDC_ACM_SendEncapsulatedCommand (void);
71 | extern int32_t USBD_CDC_ACM_GetEncapsulatedResponse (void);
72 | extern int32_t USBD_CDC_ACM_SetCommFeature (uint16_t feat);
73 | extern int32_t USBD_CDC_ACM_GetCommFeature (uint16_t feat);
74 | extern int32_t USBD_CDC_ACM_ClearCommFeature (uint16_t feat);
75 | extern int32_t USBD_CDC_ACM_SetLineCoding (void);
76 | extern int32_t USBD_CDC_ACM_GetLineCoding (void);
77 | extern int32_t USBD_CDC_ACM_SetControlLineState (uint16_t ctrl_bmp);
78 | extern int32_t USBD_CDC_ACM_SendBreak (uint16_t dur);
79 |
80 | /* USB Device user functions imported to USB Custom Class module */
81 | extern void usbd_cls_init (void);
82 | extern void usbd_cls_sof (void);
83 | extern BOOL usbd_cls_dev_req (BOOL setup);
84 | extern BOOL usbd_cls_if_req (BOOL setup);
85 | extern BOOL usbd_cls_ep_req (BOOL setup);
86 |
87 | #ifdef __cplusplus
88 | }
89 | #endif
90 |
91 | #endif /* __RL_USB_H__ */
92 |
--------------------------------------------------------------------------------
/USBStack/INC/usb.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USB_H__
17 | #define __USB_H__
18 |
19 | /* General USB header files */
20 | #include "usb_def.h"
21 | #include "usb_cdc.h"
22 | #include "usb_hid.h"
23 | #include "usb_msc.h"
24 |
25 | /* USB Device header files */
26 | #include "usbd_core.h"
27 | #include "usbd_core_cdc.h"
28 | #include "usbd_core_hid.h"
29 | #include "usbd_core_msc.h"
30 |
31 | #include "usbd_desc.h"
32 | #include "usbd_event.h"
33 | #include "usbd_cdc_acm.h"
34 | #include "usbd_hid.h"
35 | #include "usbd_msc.h"
36 | #include "usbd_hw.h"
37 |
38 | #endif /* __USB_H__ */
39 |
--------------------------------------------------------------------------------
/USBStack/INC/usb_for_lib.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USB_FOR_LIB_H__
17 | #define __USB_FOR_LIB_H__
18 |
19 | /* USB Device header files */
20 | #include "usbd_lib_cdc.h"
21 | #include "usbd_lib_hid.h"
22 | #include "usbd_lib_msc.h"
23 |
24 | /* USB System Configuration header file */
25 | #include "usb_lib.h"
26 |
27 | #endif /* __USB_FOR_LIB_H__ */
28 |
--------------------------------------------------------------------------------
/USBStack/INC/usb_lib.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USB_LIB_H__
17 | #define __USB_LIB_H__
18 |
19 | /*------------------------------------------------------------------------------
20 | * USB Device Configuration
21 | *----------------------------------------------------------------------------*/
22 | extern U8 USBD_AltSetting[];
23 | extern U8 USBD_EP0Buf[];
24 | extern const U8 usbd_power;
25 | extern const U8 usbd_hs_enable;
26 | extern const U16 usbd_if_num;
27 | extern const U8 usbd_ep_num;
28 | extern const U8 usbd_max_packet0;
29 |
30 |
31 | /*------------------------------------------------------------------------------
32 | * USB Device Class Configuration
33 | *----------------------------------------------------------------------------*/
34 | extern const U8 usbd_hid_enable;
35 | extern const U8 usbd_hid_if_num;
36 | extern const U8 usbd_hid_ep_intin;
37 | extern const U8 usbd_hid_ep_intout;
38 | extern const U16 usbd_hid_interval [2];
39 | extern const U16 usbd_hid_maxpacketsize[2];
40 | extern const U8 usbd_hid_inreport_num;
41 | extern const U8 usbd_hid_outreport_num;
42 | extern const U16 usbd_hid_inreport_max_sz;
43 | extern const U16 usbd_hid_outreport_max_sz;
44 | extern const U16 usbd_hid_featreport_max_sz;
45 | extern U16 USBD_HID_PollingCnt;
46 | extern U16 USBD_HID_PollingReload[];
47 | extern U8 USBD_HID_IdleCnt [];
48 | extern U8 USBD_HID_IdleReload [];
49 | extern U8 USBD_HID_IdleSet [];
50 | extern U8 USBD_HID_InReport [];
51 | extern U8 USBD_HID_OutReport [];
52 | extern U8 USBD_HID_FeatReport [];
53 |
54 | extern const U8 usbd_msc_enable;
55 | extern const U8 usbd_msc_if_num;
56 | extern const U8 usbd_msc_ep_bulkin;
57 | extern const U8 usbd_msc_ep_bulkout;
58 | extern const U16 usbd_msc_maxpacketsize[2];
59 | extern const U8 *usbd_msc_inquiry_data;
60 | extern U8 USBD_MSC_BulkBuf [];
61 |
62 | extern const U8 usbd_adc_enable;
63 | extern const U8 usbd_adc_cif_num;
64 | extern const U8 usbd_adc_sif1_num;
65 | extern const U8 usbd_adc_sif2_num;
66 | extern const U8 usbd_adc_ep_isoout;
67 | extern const U32 usbd_adc_cfg_datafreq;
68 | extern const U32 usbd_adc_cfg_p_s;
69 | extern const U32 usbd_adc_cfg_p_c;
70 | extern const U32 usbd_adc_cfg_b_s;
71 | extern S16 USBD_ADC_DataBuf [];
72 |
73 | extern const U8 usbd_cdc_acm_enable;
74 | extern const U8 usbd_cdc_acm_cif_num;
75 | extern const U8 usbd_cdc_acm_dif_num;
76 | extern const U8 usbd_cdc_acm_bufsize;
77 | extern const U8 usbd_cdc_acm_ep_intin;
78 | extern const U8 usbd_cdc_acm_ep_bulkin;
79 | extern const U8 usbd_cdc_acm_ep_bulkout;
80 | extern const U16 usbd_cdc_acm_sendbuf_sz;
81 | extern const U16 usbd_cdc_acm_receivebuf_sz;
82 | extern const U16 usbd_cdc_acm_maxpacketsize [2];
83 | extern const U16 usbd_cdc_acm_maxpacketsize1[2];
84 | extern U8 USBD_CDC_ACM_SendBuf [];
85 | extern U8 USBD_CDC_ACM_ReceiveBuf [];
86 | extern U8 USBD_CDC_ACM_NotifyBuf [10];
87 |
88 | extern void usbd_os_evt_set (U16 event_flags, U32 task);
89 | extern U16 usbd_os_evt_get (void);
90 | extern U32 usbd_os_evt_wait_or (U16 wait_flags, U16 timeout);
91 |
92 | extern const BOOL __rtx;
93 |
94 |
95 | /*------------------------------------------------------------------------------
96 | * USB Device Descriptors
97 | *----------------------------------------------------------------------------*/
98 | extern const U8 USBD_HID_ReportDescriptor[];
99 | extern const U16 USBD_HID_ReportDescriptorSize;
100 | extern const U16 USBD_HID_DescriptorOffset;
101 | extern const U8 USBD_DeviceDescriptor[];
102 | extern const U8 USBD_DeviceQualifier[];
103 | extern const U8 USBD_DeviceQualifier_HS[];
104 | extern const U8 USBD_ConfigDescriptor[];
105 | extern const U8 USBD_ConfigDescriptor_HS[];
106 | extern const U8 USBD_OtherSpeedConfigDescriptor[];
107 | extern const U8 USBD_OtherSpeedConfigDescriptor_HS[];
108 | extern const U8 USBD_OtherSpeedConfigDescriptor[];
109 | extern const U8 USBD_OtherSpeedConfigDescriptor_HS[];
110 | extern const U8 USBD_StringDescriptor[];
111 |
112 | #endif /* __USB_LIB_H__ */
113 |
--------------------------------------------------------------------------------
/USBStack/INC/usb_msc.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USB_MSC_H__
17 | #define __USB_MSC_H__
18 |
19 |
20 | /* MSC Subclass Codes */
21 | #define MSC_SUBCLASS_RBC 0x01
22 | #define MSC_SUBCLASS_SFF8020I_MMC2 0x02
23 | #define MSC_SUBCLASS_QIC157 0x03
24 | #define MSC_SUBCLASS_UFI 0x04
25 | #define MSC_SUBCLASS_SFF8070I 0x05
26 | #define MSC_SUBCLASS_SCSI 0x06
27 |
28 | /* MSC Protocol Codes */
29 | #define MSC_PROTOCOL_CBI_INT 0x00
30 | #define MSC_PROTOCOL_CBI_NOINT 0x01
31 | #define MSC_PROTOCOL_BULK_ONLY 0x50
32 |
33 |
34 | /* MSC Request Codes */
35 | #define MSC_REQUEST_RESET 0xFF
36 | #define MSC_REQUEST_GET_MAX_LUN 0xFE
37 |
38 |
39 | /* MSC Bulk-only Stage */
40 | #define MSC_BS_CBW 0 /* Command Block Wrapper */
41 | #define MSC_BS_DATA_OUT 1 /* Data Out Phase */
42 | #define MSC_BS_DATA_IN 2 /* Data In Phase */
43 | #define MSC_BS_DATA_IN_LAST 3 /* Data In Last Phase */
44 | #define MSC_BS_DATA_IN_LAST_STALL 4 /* Data In Last Phase with Stall */
45 | #define MSC_BS_CSW 5 /* Command Status Wrapper */
46 | #define MSC_BS_ERROR 6 /* Error */
47 |
48 |
49 | /* Bulk-only Command Block Wrapper */
50 | typedef __packed struct _MSC_CBW {
51 | U32 dSignature;
52 | U32 dTag;
53 | U32 dDataLength;
54 | U8 bmFlags;
55 | U8 bLUN;
56 | U8 bCBLength;
57 | U8 CB[16];
58 | } MSC_CBW;
59 |
60 | /* Bulk-only Command Status Wrapper */
61 | typedef __packed struct _MSC_CSW {
62 | U32 dSignature;
63 | U32 dTag;
64 | U32 dDataResidue;
65 | U8 bStatus;
66 | } MSC_CSW;
67 |
68 | #define MSC_CBW_Signature 0x43425355
69 | #define MSC_CSW_Signature 0x53425355
70 |
71 |
72 | /* CSW Status Definitions */
73 | #define CSW_CMD_PASSED 0x00
74 | #define CSW_CMD_FAILED 0x01
75 | #define CSW_PHASE_ERROR 0x02
76 |
77 |
78 | /* SCSI Commands */
79 | #define SCSI_TEST_UNIT_READY 0x00
80 | #define SCSI_REQUEST_SENSE 0x03
81 | #define SCSI_FORMAT_UNIT 0x04
82 | #define SCSI_INQUIRY 0x12
83 | #define SCSI_MODE_SELECT6 0x15
84 | #define SCSI_MODE_SENSE6 0x1A
85 | #define SCSI_START_STOP_UNIT 0x1B
86 | #define SCSI_MEDIA_REMOVAL 0x1E
87 | #define SCSI_READ_FORMAT_CAPACITIES 0x23
88 | #define SCSI_READ_CAPACITY 0x25
89 | #define SCSI_READ10 0x28
90 | #define SCSI_WRITE10 0x2A
91 | #define SCSI_VERIFY10 0x2F
92 | #define SCSI_SYNC_CACHE10 0x35
93 | #define SCSI_READ12 0xA8
94 | #define SCSI_WRITE12 0xAA
95 | #define SCSI_MODE_SELECT10 0x55
96 | #define SCSI_MODE_SENSE10 0x5A
97 | #define SCSI_SYNC_CACHE16 0x91
98 | #define SCSI_ATA_COMMAND_PASS_THROUGH12 0xA1
99 | #define SCSI_ATA_COMMAND_PASS_THROUGH16 0x85
100 | #define SCSI_SERVICE_ACTION_IN12 0xAB
101 | #define SCSI_SERVICE_ACTION_IN16 0x9E
102 | #define SCSI_SERVICE_ACTION_OUT12 0xA9
103 | #define SCSI_SERVICE_ACTION_OUT16 0x9F
104 | #define SCSI_REPORT_ID_INFO 0xA3
105 |
106 | #endif /* __USB_MSC_H__ */
107 |
--------------------------------------------------------------------------------
/USBStack/INC/usbd_cdc.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USBD_CDC_H__
17 | #define __USBD_CDC_H__
18 |
19 |
20 | /*--------------------------- Event handling routines ------------------------*/
21 |
22 | extern void usbd_vcom_serial2usb (void);
23 | extern void usbd_vcom_chkserstate (void);
24 | extern void usbd_vcom_usb2serial (void);
25 | extern void usbd_cdc_ser_flush (void);
26 |
27 | extern void USBD_CDC_SOF_Event (void);
28 |
29 | extern void USBD_CDC_EP_INTIN_Event (U32 event);
30 | extern void USBD_CDC_EP_BULKIN_Event (U32 event);
31 | extern void USBD_CDC_EP_BULKOUT_Event (U32 event);
32 | extern void USBD_CDC_EP_BULK_Event (U32 event);
33 |
34 | extern void USBD_RTX_CDC_EP_INTIN_Event (void);
35 | extern void USBD_RTX_CDC_EP_BULKIN_Event (void);
36 | extern void USBD_RTX_CDC_EP_BULKOUT_Event (void);
37 | extern void USBD_RTX_CDC_EP_BULK_Event (void);
38 |
39 |
40 | #endif /* __USBD_CDC_H__ */
41 |
--------------------------------------------------------------------------------
/USBStack/INC/usbd_cdc_acm.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USBD_CDC_ACM_H__
17 | #define __USBD_CDC_ACM_H__
18 |
19 |
20 | /*--------------------------- Event handling routines ------------------------*/
21 |
22 | extern void USBD_CDC_ACM_Reset_Event (void);
23 |
24 | extern void USBD_CDC_ACM_SOF_Event (void);
25 |
26 | extern void USBD_CDC_ACM_EP_INTIN_Event (U32 event);
27 | extern void USBD_CDC_ACM_EP_BULKIN_Event (U32 event);
28 | extern void USBD_CDC_ACM_EP_BULKOUT_Event (U32 event);
29 | extern void USBD_CDC_ACM_EP_BULK_Event (U32 event);
30 |
31 | extern __task void USBD_RTX_CDC_ACM_EP_INTIN_Event (void);
32 | extern __task void USBD_RTX_CDC_ACM_EP_BULKIN_Event (void);
33 | extern __task void USBD_RTX_CDC_ACM_EP_BULKOUT_Event (void);
34 | extern __task void USBD_RTX_CDC_ACM_EP_BULK_Event (void);
35 |
36 |
37 | #endif /* __USBD_CDC_ACM_H__ */
38 |
--------------------------------------------------------------------------------
/USBStack/INC/usbd_core.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USBD_CORE_H__
17 | #define __USBD_CORE_H__
18 |
19 |
20 | /*--------------------------- Data structures --------------------------------*/
21 |
22 | /* USB Device Core Endpoint Data Structure */
23 | typedef struct _USBD_EP_DATA {
24 | U8 *pData;
25 | U16 Count;
26 | } USBD_EP_DATA;
27 |
28 |
29 | /*--------------------------- Global variables -------------------------------*/
30 |
31 | /* USB Device Core Global Variables */
32 | extern U16 USBD_DeviceStatus;
33 | extern U8 USBD_DeviceAddress;
34 | extern U8 USBD_Configuration;
35 | extern U32 USBD_EndPointMask;
36 | extern U32 USBD_EndPointHalt;
37 | extern U32 USBD_EndPointStall;
38 | extern U8 USBD_NumInterfaces;
39 | extern U8 USBD_HighSpeed;
40 | extern U8 USBD_ZLP;
41 |
42 | extern USBD_EP_DATA USBD_EP0Data;
43 | extern USB_SETUP_PACKET USBD_SetupPacket;
44 |
45 | extern OS_TID USBD_RTX_DevTask;
46 | extern OS_TID USBD_RTX_EPTask[];
47 | extern OS_TID USBD_RTX_CoreTask;
48 |
49 |
50 | /*--------------------------- Functions exported to class specific files -----*/
51 |
52 | extern void USBD_SetupStage (void);
53 | extern void USBD_DataInStage (void);
54 | extern void USBD_DataOutStage (void);
55 | extern void USBD_StatusInStage (void);
56 | extern void USBD_StatusOutStage (void);
57 |
58 |
59 | /*--------------------------- Event handling routines ------------------------*/
60 |
61 | extern void usbd_class_init (void);
62 |
63 | extern void USBD_EndPoint0 (U32 event);
64 |
65 | extern __task void USBD_RTX_EndPoint0 (void);
66 |
67 |
68 | #endif /* __USBD_CORE_H__ */
69 |
--------------------------------------------------------------------------------
/USBStack/INC/usbd_core_cdc.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USBD_CORE_CDC_H__
17 | #define __USBD_CORE_CDC_H__
18 |
19 |
20 | /*--------------------------- Core overridable class specific functions ------*/
21 |
22 | extern BOOL USBD_EndPoint0_Setup_CDC_ReqToIF (void);
23 | extern BOOL USBD_EndPoint0_Out_CDC_ReqToIF (void);
24 |
25 |
26 | #endif /* __USBD_CORE_CDC_H__ */
27 |
--------------------------------------------------------------------------------
/USBStack/INC/usbd_core_hid.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USBD_CORE_HID_H__
17 | #define __USBD_CORE_HID_H__
18 |
19 |
20 | /*--------------------------- Core overridable class specific functions ------*/
21 |
22 | extern BOOL USBD_ReqGetDescriptor_HID (U8 **pD, U32 *len);
23 | extern BOOL USBD_EndPoint0_Setup_HID_ReqToIF (void);
24 | extern BOOL USBD_EndPoint0_Out_HID_ReqToIF (void);
25 |
26 |
27 | #endif /* __USBD_CORE_HID_H__ */
28 |
--------------------------------------------------------------------------------
/USBStack/INC/usbd_core_msc.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USBD_CORE_MSC_H__
17 | #define __USBD_CORE_MSC_H__
18 |
19 |
20 | /*--------------------------- Core overridable class specific functions ------*/
21 |
22 | extern void USBD_ReqClrFeature_MSC (U32 EPNum);
23 | extern BOOL USBD_EndPoint0_Setup_MSC_ReqToIF (void);
24 | extern BOOL USBD_EndPoint0_Out_MSC_ReqToIF (void);
25 |
26 |
27 | #endif /* __USBD_CORE_MSC_H__ */
28 |
--------------------------------------------------------------------------------
/USBStack/INC/usbd_desc.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USBD_DESC_H__
17 | #define __USBD_DESC_H__
18 |
19 | #define WBVAL(x) (x & 0xFF),((x >> 8) & 0xFF)
20 | #define B3VAL(x) (x & 0xFF),((x >> 8) & 0xFF),((x >> 16) & 0xFF)
21 | #define USB_DEVICE_DESC_SIZE (sizeof(USB_DEVICE_DESCRIPTOR))
22 | #define USB_DEVICE_QUALI_SIZE (sizeof(USB_DEVICE_QUALIFIER_DESCRIPTOR))
23 | #define USB_CONFIGUARTION_DESC_SIZE (sizeof(USB_CONFIGURATION_DESCRIPTOR))
24 | #define USB_INTERFACE_ASSOC_DESC_SIZE (sizeof(USB_INTERFACE_ASSOCIATION_DESCRIPTOR))
25 | #define USB_INTERFACE_DESC_SIZE (sizeof(USB_INTERFACE_DESCRIPTOR))
26 | #define USB_ENDPOINT_DESC_SIZE (sizeof(USB_ENDPOINT_DESCRIPTOR))
27 | #define USB_HID_DESC_SIZE (sizeof(HID_DESCRIPTOR))
28 | #define USB_HID_REPORT_DESC_SIZE (sizeof(USBD_HID_ReportDescriptor))
29 |
30 | #endif /* __USBD_DESC_H__ */
31 |
--------------------------------------------------------------------------------
/USBStack/INC/usbd_event.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USBD_EVENT_H__
17 | #define __USBD_EVENT_H__
18 |
19 |
20 | /* USB Device - Device Events */
21 | #define USBD_EVT_POWER_ON (1 << 0) /* USB Power On */
22 | #define USBD_EVT_POWER_OFF (1 << 1) /* USB Power Off */
23 | #define USBD_EVT_RESET (1 << 2) /* USB Bus Reset */
24 | #define USBD_EVT_WAKEUP (1 << 3) /* USB Remote Wakeup */
25 | #define USBD_EVT_SUSPEND (1 << 4) /* USB Suspend */
26 | #define USBD_EVT_RESUME (1 << 5) /* USB Resume */
27 | #define USBD_EVT_SOF (1 << 6) /* USB Start of Frame */
28 | #define USBD_EVT_ERROR (1 << 7) /* USB Error */
29 |
30 | /* USB Device - Endpoint Events */
31 | #define USBD_EVT_SETUP (1 << 1) /* Setup Packet */
32 | #define USBD_EVT_OUT (1 << 2) /* OUT Packet */
33 | #define USBD_EVT_IN (1 << 3) /* IN Packet */
34 | #define USBD_EVT_OUT_NAK (1 << 4) /* OUT Packet - Not Acknowledged */
35 | #define USBD_EVT_IN_NAK (1 << 5) /* IN Packet - Not Acknowledged */
36 | #define USBD_EVT_OUT_STALL (1 << 6) /* OUT Packet - Stalled */
37 | #define USBD_EVT_IN_STALL (1 << 7) /* IN Packet - Stalled */
38 | #define USBD_EVT_OUT_DMA_EOT (1 << 8) /* DMA OUT EP - End of Transfer */
39 | #define USBD_EVT_IN_DMA_EOT (1 << 9) /* DMA IN EP - End of Transfer */
40 | #define USBD_EVT_OUT_DMA_NDR (1 << 10) /* DMA OUT EP - New Descriptor Request*/
41 | #define USBD_EVT_IN_DMA_NDR (1 << 11) /* DMA IN EP - New Descriptor Request*/
42 | #define USBD_EVT_OUT_DMA_ERR (1 << 12) /* DMA OUT EP - Error */
43 | #define USBD_EVT_IN_DMA_ERR (1 << 13) /* DMA IN EP - Error */
44 |
45 | /* USB Device - Core Events */
46 | #define USBD_EVT_SET_CFG (1 << 0) /* Set Configuration */
47 | #define USBD_EVT_SET_IF (1 << 1) /* Set Interface */
48 | #define USBD_EVT_SET_FEATURE (1 << 2) /* Set Feature */
49 | #define USBD_EVT_CLR_FEATURE (1 << 3) /* Clear Feature */
50 |
51 | /* USB Device - Device Events Callback Pointers */
52 | extern void (* const USBD_P_Power_Event )(BOOL power);
53 | extern void (* const USBD_P_Reset_Event )(void);
54 | extern void (* const USBD_P_Suspend_Event )(void);
55 | extern void (* const USBD_P_Resume_Event )(void);
56 | extern void (* const USBD_P_WakeUp_Event )(void);
57 | extern void (* const USBD_P_SOF_Event )(void);
58 | extern void (* const USBD_P_Error_Event )(U32 error);
59 |
60 | /* USB Device - Endpoint Events Callback Pointers */
61 | extern void (* const USBD_P_EP[16]) (U32 event);
62 |
63 | /* USB Device - Core Events Callback Pointers */
64 | extern void (* const USBD_P_Configure_Event)(void);
65 | extern void (* const USBD_P_Interface_Event)(void);
66 | extern void (* const USBD_P_Feature_Event )(void);
67 |
68 | /* USB Device - RTX version RTX tasks initialization */
69 | extern void USBD_RTX_TaskInit (void);
70 |
71 | #endif /* __USBD_EVENT_H__ */
72 |
--------------------------------------------------------------------------------
/USBStack/INC/usbd_hid.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USBD_HID_H__
17 | #define __USBD_HID_H__
18 |
19 |
20 | /*--------------------------- Global constants -------------------------------*/
21 |
22 | /* USB HID Class API enumerated constants */
23 | enum {
24 | USBD_HID_REQ_EP_CTRL = 0, /* Request from control endpoint */
25 | USBD_HID_REQ_EP_INT, /* Request from interrupt endpoint */
26 | USBD_HID_REQ_PERIOD_UPDATE /* Request from periodic update */
27 | };
28 |
29 |
30 | /*--------------------------- Event handling routines ------------------------*/
31 |
32 | extern void USBD_HID_Configure_Event (void);
33 | extern void USBD_HID_SOF_Event (void);
34 |
35 | extern void USBD_HID_EP_INTIN_Event (U32 event);
36 | extern void USBD_HID_EP_INTOUT_Event (U32 event);
37 | extern void USBD_HID_EP_INT_Event (U32 event);
38 |
39 | extern __task void USBD_RTX_HID_EP_INTIN_Event (void);
40 | extern __task void USBD_RTX_HID_EP_INTOUT_Event(void);
41 | extern __task void USBD_RTX_HID_EP_INT_Event (void);
42 |
43 |
44 | #endif /* __USBD_HID_H__ */
45 |
--------------------------------------------------------------------------------
/USBStack/INC/usbd_hw.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USBD_HW_H__
17 | #define __USBD_HW_H__
18 |
19 |
20 | /* USB Hardware Functions */
21 | extern void USBD_Init (void);
22 | extern void USBD_Connect (BOOL con);
23 | extern void USBD_Reset (void);
24 | extern void USBD_Suspend (void);
25 | extern void USBD_Resume (void);
26 | extern void USBD_WakeUp (void);
27 | extern void USBD_WakeUpCfg (BOOL cfg);
28 | extern void USBD_SetAddress (U32 adr, U32 setup);
29 | extern void USBD_Configure (BOOL cfg);
30 | extern void USBD_ConfigEP (USB_ENDPOINT_DESCRIPTOR *pEPD);
31 | extern void USBD_DirCtrlEP (U32 dir);
32 | extern void USBD_EnableEP (U32 EPNum);
33 | extern void USBD_DisableEP (U32 EPNum);
34 | extern void USBD_ResetEP (U32 EPNum);
35 | extern void USBD_SetStallEP (U32 EPNum);
36 | extern void USBD_ClrStallEP (U32 EPNum);
37 | extern void USBD_ClearEPBuf (U32 EPNum);
38 | extern U32 USBD_ReadEP (U32 EPNum, U8 *pData);
39 | extern U32 USBD_WriteEP (U32 EPNum, U8 *pData, U32 cnt);
40 | extern U32 USBD_GetFrame (void);
41 | extern U32 USBD_GetError (void);
42 |
43 | #endif /* __USBD_HW_H__ */
44 |
--------------------------------------------------------------------------------
/USBStack/INC/usbd_lib_cdc.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USBD_LIB_CDC_H__
17 | #define __USBD_LIB_CDC_H__
18 |
19 |
20 | /*--------------------------- USB Requests -----------------------------------*/
21 |
22 | extern int32_t USBD_CDC_ACM_SendEncapsulatedCommand (void);
23 | extern int32_t USBD_CDC_ACM_GetEncapsulatedResponse (void);
24 | extern int32_t USBD_CDC_ACM_SetCommFeature (uint16_t feat);
25 | extern int32_t USBD_CDC_ACM_GetCommFeature (uint16_t feat);
26 | extern int32_t USBD_CDC_ACM_ClearCommFeature (uint16_t feat);
27 | extern int32_t USBD_CDC_ACM_SetLineCoding (void);
28 | extern int32_t USBD_CDC_ACM_GetLineCoding (void);
29 | extern int32_t USBD_CDC_ACM_SetControlLineState (uint16_t ctrl_bmp);
30 | extern int32_t USBD_CDC_ACM_SendBreak (uint16_t dur);
31 |
32 |
33 | #endif /* __USBD_LIB_CDC_H__ */
34 |
--------------------------------------------------------------------------------
/USBStack/INC/usbd_lib_hid.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USBD_LIB_HID_H__
17 | #define __USBD_LIB_HID_H__
18 |
19 |
20 | /*--------------------------- USB Requests -----------------------------------*/
21 |
22 | extern BOOL USBD_HID_GetReport (void);
23 | extern BOOL USBD_HID_SetReport (void);
24 | extern BOOL USBD_HID_GetIdle (void);
25 | extern BOOL USBD_HID_SetIdle (void);
26 | extern BOOL USBD_HID_GetProtocol (void);
27 | extern BOOL USBD_HID_SetProtocol (void);
28 |
29 |
30 | #endif /* __USBD_LIB_HID_H__ */
31 |
--------------------------------------------------------------------------------
/USBStack/INC/usbd_lib_msc.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USBD_LIB_MSC_H__
17 | #define __USBD_LIB_MSC_H__
18 |
19 |
20 | /*--------------------------- USB Requests -----------------------------------*/
21 |
22 | extern void USBD_MSC_ClrStallEP(U32 EPNum);
23 | extern BOOL USBD_MSC_Reset (void);
24 | extern BOOL USBD_MSC_GetMaxLUN (void);
25 | extern void USBD_MSC_GetCBW (void);
26 | extern void USBD_MSC_SetCSW (void);
27 |
28 |
29 | #endif /* __USBD_LIB_MSC_H__ */
30 |
--------------------------------------------------------------------------------
/USBStack/INC/usbd_msc.h:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #ifndef __USBD_MSC_H__
17 | #define __USBD_MSC_H__
18 |
19 |
20 | /*--------------------------- Global variables -------------------------------*/
21 |
22 | /* USB Device Mass Storage Device Class Global Variables */
23 | extern BOOL USBD_MSC_MediaReady;
24 | extern BOOL USBD_MSC_ReadOnly;
25 | extern U32 USBD_MSC_MemorySize;
26 | extern U32 USBD_MSC_BlockSize;
27 | extern U32 USBD_MSC_BlockGroup;
28 | extern U32 USBD_MSC_BlockCount;
29 | extern U8 *USBD_MSC_BlockBuf;
30 |
31 |
32 | /*--------------------------- Event handling routines ------------------------*/
33 |
34 | extern void USBD_MSC_EP_BULKIN_Event (U32 event);
35 | extern void USBD_MSC_EP_BULKOUT_Event (U32 event);
36 | extern void USBD_MSC_EP_BULK_Event (U32 event);
37 |
38 | extern __task void USBD_RTX_MSC_EP_BULKIN_Event (void);
39 | extern __task void USBD_RTX_MSC_EP_BULKOUT_Event (void);
40 | extern __task void USBD_RTX_MSC_EP_BULK_Event (void);
41 |
42 |
43 | #endif /* __USBD_MSC_H__ */
44 |
--------------------------------------------------------------------------------
/USBStack/SRC/usbd_core_msc.c:
--------------------------------------------------------------------------------
1 | /* CMSIS-DAP Interface Firmware
2 | * Copyright (c) 2009-2013 ARM Limited
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | */
16 | #include "RTL.h"
17 | #include "rl_usb.h"
18 | #include "string.h"
19 | #include "usb_for_lib.h"
20 |
21 |
22 | /*
23 | * Clear Feature USB Device Request - MSC specific handling
24 | * Parameters: EPNum: Endpoint number
25 | * Return Value: None
26 | */
27 |
28 | __weak void USBD_ReqClrFeature_MSC (U32 EPNum) {
29 | USBD_MSC_ClrStallEP (EPNum);
30 | }
31 |
32 |
33 | /*
34 | * USB Device Endpoint 0 Event Callback - MSC specific handling (Setup Request To Interface)
35 | * Parameters: none
36 | * Return Value: TRUE - Setup class request ok, FALSE - Setup class request not supported
37 | */
38 |
39 | __weak BOOL USBD_EndPoint0_Setup_MSC_ReqToIF (void) {
40 | if (USBD_SetupPacket.wIndexL == usbd_msc_if_num) { /* IF number correct? */
41 | switch (USBD_SetupPacket.bRequest) {
42 | case MSC_REQUEST_RESET:
43 | if ((USBD_SetupPacket.wValue == 0) && /* RESET with invalid parameters -> STALL */
44 | (USBD_SetupPacket.wLength == 0)) {
45 | if (USBD_MSC_Reset()) {
46 | USBD_StatusInStage();
47 | return (__TRUE);
48 | }
49 | }
50 | break;
51 | case MSC_REQUEST_GET_MAX_LUN:
52 | if ((USBD_SetupPacket.wValue == 0) && /* GET_MAX_LUN with invalid parameters -> STALL */
53 | (USBD_SetupPacket.wLength == 1)) {
54 | if (USBD_MSC_GetMaxLUN()) {
55 | USBD_EP0Data.pData = USBD_EP0Buf;
56 | USBD_DataInStage();
57 | return (__TRUE);
58 | }
59 | }
60 | break;
61 | }
62 | }
63 | return (__FALSE);
64 | }
65 |
--------------------------------------------------------------------------------
/内环PID调试日志.txt:
--------------------------------------------------------------------------------
1 | 日期 时间 调试人 P I D 效果(描述或截图名称,截图可以按PID的值命名)
2 | 20180531 10:56 张硕 800 100 2000 默认值()
--------------------------------------------------------------------------------
/当前程序状态描述.txt:
--------------------------------------------------------------------------------
1 | /********************************************************当前程序状态描述***************************************************************
2 | 定高模式:不定高(油门值为当前手柄值)
3 | 对于待速的描述:对于一般飞机,解锁后电机开始旋转为最低设定速度。对于该程序,当手柄为<100时,为0,当>100时才会到达最低转速。(这样比较省电)
4 | USB通信状态:不适用USB通信
5 | 串口通信状态:使用串口通信
6 | 串口波特率:115200
7 | 下位机传输速度:匿名发送速度(较快,但容易丢帧)
8 | 对于程序指示状态描述:
9 | LED指示灯:
10 | L1用于指示GPS所搜索到的卫星个数。
11 | 自稳模式:
12 | 锁定状态下:L2,L3,L4指示灯呼吸闪烁
13 | 解锁状态下:L2,L3,L4指示灯常亮
14 | 气压定高模式:
15 | 锁定状态下:L3,L4指示灯呼吸闪烁
16 | 解锁状态下:L3,L4指示灯常亮
17 | 超声定高模式:
18 | 锁定状态下:L2,L3指示灯呼吸闪烁
19 | 解锁状态下:L2,L3指示灯常亮
20 | 磁力计校准模式:
21 | L2,L4指示灯闪烁,L3熄灭
22 | 蜂鸣器:
23 | 飞控上电瞬间蜂鸣器会有1s的长鸣
24 | 任意模式下解锁时会有2s的长鸣
25 | 从解锁状态切入锁定状态会有1s的长鸣
26 | 在解锁状态下,油门很低时每隔10s会有250ms的短鸣提示
27 | 在电池电压低于11v时蜂鸣器常鸣
28 | ***************************************************************************************************************************************/
29 | 日期 时间 更改人 更改内容
30 |
--------------------------------------------------------------------------------
/程序调试日志.txt:
--------------------------------------------------------------------------------
1 | 日期 时间 调试人 调试模块 调试内容
2 | 20180531 10:43 张硕 date_transfer.c 对于内环调试:手柄期望通道范围0-1000,角度范围为+-25,角速度范围为+-250,故将输出的比例进行调整,此时可根据波形跟踪进行内环PID参数的调试。
3 | ctrl.c 将内环角速度控制的放大系数减小为2(原值为3),目的是减小前馈的调节比例,使外环对内环的影响降低。
4 | device_beep 增加蜂鸣器驱动设备
5 | device_power 增加电池电压检测设备
6 | driver_beep 增加蜂鸣器API
7 | driver_power 增加电池电压API
8 | 20180602 20:56 张硕 imu.c 将yaw角的矫正速度更改为解锁状态增益0.2(原值0.1),锁定状态下增益为1.5(原值为0.2)(目前为原值后期在看情况进行调试)
9 | 20180605 19:29 张硕 height_ctrl.c LIN333:将期望度的计算方式进行更改,需要检验超声波定高的效果。
10 | LIN272:将自调节的幅度降低,在调试阶段一切自调节的范围都应该要小。
11 | LIN255:增加飞行器速度计算,可根据手柄不动时飞行器是否有左右或前后速度来矫正ACC的基值。
12 | LIN48:增加速度判断变量
13 | position_control.c LIN181:将位置控制速度限幅为800ms/s(原值2000)。
14 | LIN185:将期望速度的输出限幅为1200(原值为3000)。
15 | LIN212将积分转换为的角度进行限幅为8(原值为20)。
16 | LIN216:将位置环角度输出限幅为12(原值为30)目的是调试阶段降低自调节幅度防止炸鸡。
17 | rc.c LIN326:增加GPS遥控控制模式
18 | 20180610 7:25 张硕 position_control.c LIN115:更改位置模式进入条件,当高度控制模式开启之后方可进入GPS位置控制,因为GPS控制的内环是速度环,该速度环的速度是在高度控制中计算出的。
19 | LIN166:增加初始位置标定判断,防止上电直接进入GPS定点模式。如果直接进入GPS定点模式会导致很多变量直接溢出,导致不可控的后果。
20 | LIN234:将初始位置标记位之一。
21 | LIN248:当没有进行位置标记,不可以将位置控制模式切换为3。
22 | driver_GPS.c LIN476:增加GPS看门狗,当1s没有接收到GPS信息时将GPS结构体清零。为了防止GPS故障时还在GPS定点模式,此时飞机会出现不可预估的动作。
23 | LIN211:将RS的类型更改为double,此时数据才不会溢出。
24 | driver_usart.c LIN151:当接收到GPS信号时给GPS看门狗喂狗。
25 | OFposition_control.c 增加光流定点控制模块。该模块采用抗积分饱和PID控制。控制效果还不错。
26 |
--------------------------------------------------------------------------------
/软件版权声明.txt:
--------------------------------------------------------------------------------
1 | 该软件是由中国民航大学机器人研究所无人机控制实验室由Light飞控代码(EMIDE)开发环境下移植到KEIL
2 | 开发环境下,同时对改代码进行了大量的优化和功能上的增加。该代码的解释权由中国民航大学所有,禁止
3 | 商业使用,同时如有使用请注明出处。
--------------------------------------------------------------------------------
/遥控控制位置控制模式.txt:
--------------------------------------------------------------------------------
1 | /*旋钮控制位置模式切换方式*/
2 | /* 定高模式切换 由AUX1三档控制*/
3 | /* 辅助1通道在1000-1299 */
4 | if( CH_filter[AUX1] < -200 )
5 | /* ,非定高模式 */
6 | height_ctrl_mode = 0;
7 | /* 辅助1通道在1300-1699 */
8 | else if( CH_filter[AUX1] < 200 )
9 | /* 气压定高模式 */
10 | height_ctrl_mode = 1;
11 | /* 辅助1通道在1700-2000 */
12 | else
13 | {
14 | /* 超声波定高模式 */
15 | if(ultra_ok == 1)
16 | height_ctrl_mode = 2;
17 | /* 没有超声波就是气压定高模式 */
18 | else
19 | height_ctrl_mode = 1;
20 | }
21 |
22 | /* 位置模式切换 由AUX2三档控制*/
23 | /* 辅助2通道在1000-1299 */
24 | if( CH_filter[AUX2] > -200 && CH_filter[AUX2] < 200)
25 | /* 不悬停模式 */
26 | position_ctrl_mode = 1;
27 | /* 辅助2通道在1300-1699 */
28 | else if( CH_filter[AUX2] < -200 )
29 | {
30 | /* 航向锁定模式 */
31 | if(gpsx.fixmode >= 2)
32 | position_ctrl_mode = 2;
33 | /* 没有接收到GPS信号则切换为不悬停模式 */
34 | else
35 | position_ctrl_mode = 1;
36 | }
37 | /* 辅助2通道在1700-2000 */
38 | else
39 | {
40 | /* GPS定位模式 */
41 | if(gpsx.fixmode >= 2)
42 | position_ctrl_mode = 3;
43 | /* 没有接收到GPS信号则切换为不悬停模式 */
44 | else
45 | position_ctrl_mode = 1;
46 | }
--------------------------------------------------------------------------------