test
Dependencies: mbed-rtos mbed ros_kinetic
Revision 0:9646fc4e3fae, committed 2017-05-19
- Comitter:
- randalthor
- Date:
- Fri May 19 09:12:45 2017 +0000
- Commit message:
- test
Changed in this revision
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/main.cpp Fri May 19 09:12:45 2017 +0000 @@ -0,0 +1,543 @@ +#include "mbed.h" +#include "cmsis_os.h" +#include "main.h" +#include "stm32f7xx_hal.h" +#include <ros.h> +#include <geometry_msgs/Twist.h> +#include <geometry_msgs/Vector3.h> +#include <openlab/mobileRobot.h> +#include <std_msgs/String.h> +#include <std_msgs/Float32.h> +#include <std_msgs/Bool.h> + +#define pi 3.1416 //for angular velocity calculation +#define length 0.3 //distance between 2 wheel - meter +#define radius 0.036 //radius of wheel with load - meter +#define timeConst 0.00926 //time constant + +/*Global variables*/ +int8_t ADC_buffer[2]; +int32_t encoder1_1 = 0; +int32_t encoder1=0; +int32_t encoder2_1 = 0; +int32_t encoder2=0; +float pwmLeft=0; +float pwmRight=0; +float dc_current1=0; +float dc_current2=0; +double real_velocity_linx=0; +double real_velocity_angz=0; +double cmd_velocity_linx=0; +double cmd_velocity_angz=0; + +float kp_left = 39; +float kd_left = 2; +float ki_left = 10; +float kp_right = 39; +float kd_right = 2; +float ki_right = 10; +double errDirVel_1 = 0; +double errAngVel_1 = 0; +double errorLeft = 0; +double errorRight = 0; +double errorLeft_1 = 0; +double errorRight_1 = 0; +double linearLeft = 0; +double linearRight = 0; +double driveLeft = 0; +double driveRight = 0; +double iLeft = 0; +double iRight = 0; + +float i_max = 1000; +float dLeft = 0; +float dRight = 0; + +int diff1=0; +int diff2=0; +float current1; +float current2; + + + +ros::NodeHandle nh; +openlab::mobileRobot str_msg; +ros::Publisher RobotFeedback("RobotFeedback", &str_msg); + +void callback_vel( const geometry_msgs::Twist& vel){ + + cmd_velocity_linx = vel.linear.x; + cmd_velocity_angz = vel.angular.z; + + + nh.spinOnce(); + osDelay(10); +} + +ros::Subscriber<geometry_msgs::Twist> sub("cmd_vel", callback_vel ); + +/*loop control*/ +//DigitalOut led1(LED1); +DigitalOut led2(LED2); +DigitalOut led3(LED3); +/* USER CODE BEGIN Includes */ + +/* USER CODE END Includes */ + +/* Private variables ---------------------------------------------------------*/ +ADC_HandleTypeDef hadc2; +DMA_HandleTypeDef hdma_adc2; + +TIM_HandleTypeDef htim1; +TIM_HandleTypeDef htim4; +TIM_HandleTypeDef htim9; + + +/* Private function prototypes -----------------------------------------------*/ + +void Error_Handler(void); +static void MX_GPIO_Init(void); +static void MX_DMA_Init(void); +static void MX_ADC2_Init(void); +static void MX_TIM1_Init(void); +static void MX_TIM4_Init(void); +static void MX_TIM9_Init(void); + +void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim); + +void feedback_thread(void const *args) +{ + while (true) { + + + str_msg.pwm_1 = pwmLeft; + str_msg.pwm_2 = pwmRight; + str_msg.real_velocity_linx = real_velocity_linx; + str_msg.real_velocity_angz = real_velocity_angz; + str_msg.cmd_velocity_linx = cmd_velocity_linx; + str_msg.cmd_velocity_angz = cmd_velocity_angz; + str_msg.dc_current_1 = current1; + str_msg.dc_current_2 = current2; + str_msg.encoder_1 = encoder1; + str_msg.encoder_2 = encoder2; + RobotFeedback.publish( &str_msg ); + nh.spinOnce(); + osDelay(10); + + } +} + +void velocity_control(void const *args) +{ + + while (true) { + + current1 = ADC_buffer[0]; + current2 = ADC_buffer[1]; + encoder1 = TIM1->CNT; + encoder2 = TIM4->CNT; + + + diff1=encoder1 - encoder1_1; + diff2=encoder2 - encoder2_1; + + if(diff1 < - 30000) diff1 = diff1 + 65536; + if(diff1 > 30000) diff1 = diff1 - 65536; + if(diff2 < - 30000) diff2 = diff2 + 65536; + if(diff2> 30000) diff2 = diff2 - 65536; + + linearLeft = diff1 * 0.000748*200*radius; + linearRight = diff2 * 0.000748*200*radius; + + real_velocity_linx = (linearLeft + linearRight) * 0.5; + real_velocity_angz = (linearRight - linearLeft) * 5.8824; + + encoder1_1 = encoder1; + encoder2_1 = encoder2; + + driveLeft = cmd_velocity_linx - (0.17 * cmd_velocity_angz * 0.5); + driveRight = cmd_velocity_linx + (0.17 * cmd_velocity_angz * 0.5); + + errorLeft = driveLeft - linearLeft; + errorRight = driveRight - linearRight; + + iRight = iRight + (errorRight * 1); + iLeft = iLeft + (errorLeft * 1); + dLeft = (errorLeft - errorLeft_1) * 200; + dRight = (errorRight - errorRight_1) * 200; + + errorLeft_1 = errorLeft; + errorRight_1 = errorRight; + + if(iRight > i_max) iRight = i_max; + if(iRight < -i_max) iRight = i_max; + if(iLeft > i_max) iLeft = i_max; + if(iLeft < -i_max) iLeft = i_max; + + pwmLeft = kp_left * errorLeft + ki_left * iLeft + kd_left * dLeft; + pwmRight = kp_right * errorRight + ki_right * iRight + kd_right * dRight; + //HAL_GPIO_TogglePin(GPIOB, GPIO_PIN_0); + + + if(cmd_velocity_linx || cmd_velocity_angz) + { + + + + + if(pwmLeft>0) + { + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_3, GPIO_PIN_SET); + //wait(0.005); + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_4, GPIO_PIN_RESET); + //wait(0.005); + pwmLeft = 61 + pwmLeft; + } + if (pwmLeft<0) + { + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_3, GPIO_PIN_RESET); + // wait(0.005); + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_4, GPIO_PIN_SET); + //wait(0.005); + pwmLeft = 61 - pwmLeft; + } + if(pwmRight>0) + { + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_SET); + //wait(0.005); + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_15, GPIO_PIN_RESET); + //wait(0.005); + pwmRight = 60 + pwmRight; + } + if(pwmRight<0) + { + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14, GPIO_PIN_RESET); + //wait(0.005); + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_15, GPIO_PIN_SET); + // wait(0.005); + pwmRight = 60 - pwmRight; + } + + + } + else + { + pwmRight = 0; + pwmLeft = 0; + iRight = 0; + iLeft = 0; + } + + if(pwmRight > 99) pwmRight = 99; + if(pwmRight < -99) pwmRight = -99; + if(pwmLeft > 99) pwmLeft = 99; + if(pwmLeft < -99) pwmLeft = -99; + + __HAL_TIM_SetCompare(&htim9, TIM_CHANNEL_1, pwmLeft); + __HAL_TIM_SetCompare(&htim9, TIM_CHANNEL_2, pwmRight); + + //htim9.Instance->CCR1 = pwm1; + // htim9.Instance->CCR2 = pwm2; + + + osDelay(5); + + + } +} + + osThreadDef(feedback_thread, osPriorityNormal, DEFAULT_STACK_SIZE); + osThreadDef(velocity_control, osPriorityNormal, DEFAULT_STACK_SIZE); + + +int main() +{ + +/* Reset of all peripherals, Initializes the Flash interface and the Systick. */ + HAL_Init(); + + + /* Initialize all configured peripherals */ + MX_GPIO_Init(); + MX_DMA_Init(); + MX_ADC2_Init(); + MX_TIM1_Init(); + MX_TIM4_Init(); + MX_TIM9_Init(); + + /*Initialize necessery configuration*/ + HAL_ADC_Start_DMA(&hadc2, (uint32_t *)ADC_buffer, 2); + HAL_TIM_Encoder_Start(&htim1, TIM_CHANNEL_1|TIM_CHANNEL_2); + HAL_TIM_Encoder_Start(&htim4, TIM_CHANNEL_1|TIM_CHANNEL_2); + HAL_TIM_PWM_Start(&htim9, TIM_CHANNEL_1); + HAL_TIM_PWM_Start(&htim9, TIM_CHANNEL_2); + + nh.initNode(); + nh.advertise(RobotFeedback); + nh.subscribe(sub); + + printf("\n\n*** RTOS basic example ***\n"); + + + osThreadCreate(osThread(feedback_thread), NULL); + osThreadCreate(osThread(velocity_control), NULL); + + + while (true) { + led2 = !led2; + osDelay(500); + } +} + + /* TIM1 init function */ +static void MX_TIM1_Init(void) +{ + + TIM_Encoder_InitTypeDef sConfig; + TIM_MasterConfigTypeDef sMasterConfig; + + htim1.Instance = TIM1; + htim1.Init.Prescaler = 0; + htim1.Init.CounterMode = TIM_COUNTERMODE_UP; + htim1.Init.Period = 65535; + htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + htim1.Init.RepetitionCounter = 0; + sConfig.EncoderMode = TIM_ENCODERMODE_TI12; + sConfig.IC1Polarity = TIM_ICPOLARITY_RISING; + sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI; + sConfig.IC1Prescaler = TIM_ICPSC_DIV1; + sConfig.IC1Filter = 0; + sConfig.IC2Polarity = TIM_ICPOLARITY_RISING; + sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; + sConfig.IC2Prescaler = TIM_ICPSC_DIV1; + sConfig.IC2Filter = 0; + if (HAL_TIM_Encoder_Init(&htim1, &sConfig) != HAL_OK) + { + Error_Handler(); + } + + sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; + sMasterConfig.MasterOutputTrigger2 = TIM_TRGO2_RESET; + sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; + if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK) + { + Error_Handler(); + } + +} + +/* TIM4 init function */ +static void MX_TIM4_Init(void) +{ + + TIM_Encoder_InitTypeDef sConfig; + TIM_MasterConfigTypeDef sMasterConfig; + + htim4.Instance = TIM4; + htim4.Init.Prescaler = 0; + htim4.Init.CounterMode = TIM_COUNTERMODE_UP; + htim4.Init.Period = 65535; + htim4.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + sConfig.EncoderMode = TIM_ENCODERMODE_TI12; + sConfig.IC1Polarity = TIM_ICPOLARITY_RISING; + sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI; + sConfig.IC1Prescaler = TIM_ICPSC_DIV1; + sConfig.IC1Filter = 0; + sConfig.IC2Polarity = TIM_ICPOLARITY_RISING; + sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI; + sConfig.IC2Prescaler = TIM_ICPSC_DIV1; + sConfig.IC2Filter = 0; + if (HAL_TIM_Encoder_Init(&htim4, &sConfig) != HAL_OK) + { + Error_Handler(); + } + + sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; + sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; + if (HAL_TIMEx_MasterConfigSynchronization(&htim4, &sMasterConfig) != HAL_OK) + { + Error_Handler(); + } + +} + +/* ADC2 init function */ +static void MX_ADC2_Init(void) +{ + + ADC_ChannelConfTypeDef sConfig; + + /**Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion) + */ + hadc2.Instance = ADC2; + hadc2.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV2; + hadc2.Init.Resolution = ADC_RESOLUTION_8B; + hadc2.Init.ScanConvMode = ENABLE; + hadc2.Init.ContinuousConvMode = ENABLE; + hadc2.Init.DiscontinuousConvMode = DISABLE; + hadc2.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE; + hadc2.Init.ExternalTrigConv = ADC_SOFTWARE_START; + hadc2.Init.DataAlign = ADC_DATAALIGN_RIGHT; + hadc2.Init.NbrOfConversion = 2; + hadc2.Init.DMAContinuousRequests = ENABLE; + hadc2.Init.EOCSelection = ADC_EOC_SINGLE_CONV; + if (HAL_ADC_Init(&hadc2) != HAL_OK) + { + Error_Handler(); + } + + /**Configure for the selected ADC regular channel its corresponding rank in the sequencer and its sample time. + */ + sConfig.Channel = ADC_CHANNEL_5; + sConfig.Rank = 1; + sConfig.SamplingTime = ADC_SAMPLETIME_144CYCLES; + if (HAL_ADC_ConfigChannel(&hadc2, &sConfig) != HAL_OK) + { + Error_Handler(); + } + + /**Configure for the selected ADC regular channel its corresponding rank in the sequencer and its sample time. + */ + sConfig.Channel = ADC_CHANNEL_6; + sConfig.Rank = 2; + if (HAL_ADC_ConfigChannel(&hadc2, &sConfig) != HAL_OK) + { + Error_Handler(); + } + +} + +/* TIM9 init function */ +static void MX_TIM9_Init(void) +{ + + TIM_OC_InitTypeDef sConfigOC; + + htim9.Instance = TIM9; + htim9.Init.Prescaler = 215; + htim9.Init.CounterMode = TIM_COUNTERMODE_UP; + htim9.Init.Period = 99; + htim9.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + if (HAL_TIM_PWM_Init(&htim9) != HAL_OK) + { + Error_Handler(); + } + + sConfigOC.OCMode = TIM_OCMODE_PWM1; + sConfigOC.Pulse = 0; + sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; + sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; + if (HAL_TIM_PWM_ConfigChannel(&htim9, &sConfigOC, TIM_CHANNEL_1) != HAL_OK) + { + Error_Handler(); + } + + if (HAL_TIM_PWM_ConfigChannel(&htim9, &sConfigOC, TIM_CHANNEL_2) != HAL_OK) + { + Error_Handler(); + } + + HAL_TIM_MspPostInit(&htim9); + +} + +/** + * Enable DMA controller clock + */ +static void MX_DMA_Init(void) +{ + /* DMA controller clock enable */ + __HAL_RCC_DMA2_CLK_ENABLE(); + + /* DMA interrupt init */ + /* DMA2_Stream2_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DMA2_Stream2_IRQn, 0, 0); + HAL_NVIC_EnableIRQ(DMA2_Stream2_IRQn); + +} + +/** Configure pins as + * Analog + * Input + * Output + * EVENT_OUT + * EXTI +*/ +static void MX_GPIO_Init(void) +{ + + GPIO_InitTypeDef GPIO_InitStruct; + + /* GPIO Ports Clock Enable */ + __HAL_RCC_GPIOE_CLK_ENABLE(); + __HAL_RCC_GPIOA_CLK_ENABLE(); + __HAL_RCC_GPIOB_CLK_ENABLE(); + __HAL_RCC_GPIOD_CLK_ENABLE(); + + /*Configure GPIO pin Output Level */ + HAL_GPIO_WritePin(GPIOB, GPIO_PIN_0, GPIO_PIN_RESET); + + /*Configure GPIO pin Output Level */ + HAL_GPIO_WritePin(GPIOD, GPIO_PIN_14|GPIO_PIN_15|GPIO_PIN_3|GPIO_PIN_4, GPIO_PIN_RESET); + + /*Configure GPIO pin : PB0 */ + GPIO_InitStruct.Pin = GPIO_PIN_0; + GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + + /*Configure GPIO pins : PD14 PD15 PD3 PD4 */ + GPIO_InitStruct.Pin = GPIO_PIN_14|GPIO_PIN_15|GPIO_PIN_3|GPIO_PIN_4; + GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); + +} +/* USER CODE BEGIN 4 */ + +/* USER CODE END 4 */ + +/** + * @brief This function is executed in case of error occurrence. + * @param None + * @retval None + */ +void Error_Handler(void) +{ + /* USER CODE BEGIN Error_Handler */ + /* User can add his own implementation to report the HAL error return state */ + while(1) + { + } + /* USER CODE END Error_Handler */ +} + +void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim) +{ + + GPIO_InitTypeDef GPIO_InitStruct; + if(htim->Instance==TIM9) + { + /* USER CODE BEGIN TIM9_MspPostInit 0 */ + + /* USER CODE END TIM9_MspPostInit 0 */ + + /**TIM9 GPIO Configuration + PE5 ------> TIM9_CH1 + PE6 ------> TIM9_CH2 + */ + GPIO_InitStruct.Pin = GPIO_PIN_5|GPIO_PIN_6; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + GPIO_InitStruct.Alternate = GPIO_AF3_TIM9; + HAL_GPIO_Init(GPIOE, &GPIO_InitStruct); + + /* USER CODE BEGIN TIM9_MspPostInit 1 */ + + /* USER CODE END TIM9_MspPostInit 1 */ + } + +} \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/main.h Fri May 19 09:12:45 2017 +0000 @@ -0,0 +1,58 @@ +/** + ****************************************************************************** + * File Name : main.h + * Description : This file contains the common defines of the application + ****************************************************************************** + * + * COPYRIGHT(c) 2017 STMicroelectronics + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __MAIN_H +#define __MAIN_H + /* Includes ------------------------------------------------------------------*/ + +/* USER CODE BEGIN Includes */ + +/* USER CODE END Includes */ + +/* Private define ------------------------------------------------------------*/ + +/* USER CODE BEGIN Private defines */ + +/* USER CODE END Private defines */ + +/** + * @} + */ + +/** + * @} +*/ + +#endif /* __MAIN_H */ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos.lib Fri May 19 09:12:45 2017 +0000 @@ -0,0 +1,1 @@ +http://mbed.org/users/mbed_official/code/mbed-rtos/#58563e6cba1e
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed.bld Fri May 19 09:12:45 2017 +0000 @@ -0,0 +1,1 @@ +https://mbed.org/users/mbed_official/code/mbed/builds/97feb9bacc10 \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ros_lib_kinetic.lib Fri May 19 09:12:45 2017 +0000 @@ -0,0 +1,1 @@ +https://developer.mbed.org/users/randalthor/code/ros_kinetic/#af816ffd33df
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/stm32f7xx_hal.h Fri May 19 09:12:45 2017 +0000 @@ -0,0 +1,254 @@ +/** + ****************************************************************************** + * @file stm32f7xx_hal.h + * @author MCD Application Team + * @version V1.1.2 + * @date 23-September-2016 + * @brief This file contains all the functions prototypes for the HAL + * module driver. + ****************************************************************************** + * @attention + * + * <h2><center>© COPYRIGHT(c) 2016 STMicroelectronics</center></h2> + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F7xx_HAL_H +#define __STM32F7xx_HAL_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f7xx_hal_conf.h" + +/** @addtogroup STM32F7xx_HAL_Driver + * @{ + */ + +/** @addtogroup HAL + * @{ + */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/** @defgroup SYSCFG_Exported_Constants SYSCFG Exported Constants + * @{ + */ + +/** @defgroup SYSCFG_BootMode Boot Mode + * @{ + */ +#define SYSCFG_MEM_BOOT_ADD0 ((uint32_t)0x00000000U) +#define SYSCFG_MEM_BOOT_ADD1 SYSCFG_MEMRMP_MEM_BOOT +/** + * @} + */ + +/** + * @} + */ + +/* Exported macro ------------------------------------------------------------*/ +/** @defgroup HAL_Exported_Macros HAL Exported Macros + * @{ + */ + +/** @brief Freeze/Unfreeze Peripherals in Debug mode + */ +#define __HAL_DBGMCU_FREEZE_TIM2() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM2_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM3() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM3_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM4() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM4_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM5() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM5_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM6() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM6_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM7() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM7_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM12() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM12_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM13() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM13_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM14() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM14_STOP)) +#define __HAL_DBGMCU_FREEZE_LPTIM1() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_LPTIM1_STOP)) +#define __HAL_DBGMCU_FREEZE_RTC() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_RTC_STOP)) +#define __HAL_DBGMCU_FREEZE_WWDG() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_WWDG_STOP)) +#define __HAL_DBGMCU_FREEZE_IWDG() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_IWDG_STOP)) +#define __HAL_DBGMCU_FREEZE_I2C1_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT)) +#define __HAL_DBGMCU_FREEZE_I2C2_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C2_SMBUS_TIMEOUT)) +#define __HAL_DBGMCU_FREEZE_I2C3_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT)) +#define __HAL_DBGMCU_FREEZE_I2C4_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C4_SMBUS_TIMEOUT)) +#define __HAL_DBGMCU_FREEZE_CAN1() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_CAN1_STOP)) +#define __HAL_DBGMCU_FREEZE_CAN2() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_CAN2_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM1() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM1_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM8() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM8_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM9() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM9_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM10() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM10_STOP)) +#define __HAL_DBGMCU_FREEZE_TIM11() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM11_STOP)) + +#define __HAL_DBGMCU_UNFREEZE_TIM2() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM2_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM3() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM3_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM4() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM4_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM5() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM5_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM6() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM6_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM7() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM7_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM12() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM12_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM13() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM13_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM14() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM14_STOP)) +#define __HAL_DBGMCU_UNFREEZE_LPTIM1() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_LPTIM1_STOP)) +#define __HAL_DBGMCU_UNFREEZE_RTC() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_RTC_STOP)) +#define __HAL_DBGMCU_UNFREEZE_WWDG() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_WWDG_STOP)) +#define __HAL_DBGMCU_UNFREEZE_IWDG() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_IWDG_STOP)) +#define __HAL_DBGMCU_UNFREEZE_I2C1_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT)) +#define __HAL_DBGMCU_UNFREEZE_I2C2_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C2_SMBUS_TIMEOUT)) +#define __HAL_DBGMCU_UNFREEZE_I2C3_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT)) +#define __HAL_DBGMCU_UNFREEZE_I2C4_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C4_SMBUS_TIMEOUT)) +#define __HAL_DBGMCU_UNFREEZE_CAN1() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_CAN1_STOP)) +#define __HAL_DBGMCU_UNFREEZE_CAN2() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_CAN2_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM1() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM1_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM8() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM8_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM9() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM9_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM10() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM10_STOP)) +#define __HAL_DBGMCU_UNFREEZE_TIM11() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM11_STOP)) + + +/** @brief FMC (NOR/RAM) mapped at 0x60000000 and SDRAM mapped at 0xC0000000 + */ +#define __HAL_SYSCFG_REMAPMEMORY_FMC() (SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_SWP_FMC)) + + +/** @brief FMC/SDRAM mapped at 0x60000000 (NOR/RAM) mapped at 0xC0000000 + */ +#define __HAL_SYSCFG_REMAPMEMORY_FMC_SDRAM() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_SWP_FMC);\ + SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_SWP_FMC_0);\ + }while(0); +/** + * @brief Return the memory boot mapping as configured by user. + * @retval The boot mode as configured by user. The returned value can be one + * of the following values: + * @arg @ref SYSCFG_MEM_BOOT_ADD0 + * @arg @ref SYSCFG_MEM_BOOT_ADD1 + */ +#define __HAL_SYSCFG_GET_BOOT_MODE() READ_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_MEM_BOOT) + +#if defined (STM32F765xx) || defined (STM32F767xx) || defined (STM32F769xx) || defined (STM32F777xx) || defined (STM32F779xx) +/** @brief SYSCFG Break Cortex-M7 Lockup lock. + * Enable and lock the connection of Cortex-M7 LOCKUP (Hardfault) output to TIM1/8 Break input. + * @note The selected configuration is locked and can be unlocked only by system reset. + */ +#define __HAL_SYSCFG_BREAK_LOCKUP_LOCK() SET_BIT(SYSCFG->CBR, SYSCFG_CBR_CLL) + +/** @brief SYSCFG Break PVD lock. + * Enable and lock the PVD connection to Timer1/8 Break input, as well as the PVDE and PLS[2:0] in the PWR_CR1 register. + * @note The selected configuration is locked and can be unlocked only by system reset. + */ +#define __HAL_SYSCFG_BREAK_PVD_LOCK() SET_BIT(SYSCFG->CBR, SYSCFG_CBR_PVDL) +#endif /* STM32F765xx || STM32F767xx || STM32F769xx || STM32F777xx || STM32F779xx */ + +/** + * @} + */ + +/* Exported functions --------------------------------------------------------*/ +/** @addtogroup HAL_Exported_Functions + * @{ + */ +/** @addtogroup HAL_Exported_Functions_Group1 + * @{ + */ +/* Initialization and de-initialization functions ******************************/ +HAL_StatusTypeDef HAL_Init(void); +HAL_StatusTypeDef HAL_DeInit(void); +void HAL_MspInit(void); +void HAL_MspDeInit(void); +HAL_StatusTypeDef HAL_InitTick (uint32_t TickPriority); +/** + * @} + */ + +/** @addtogroup HAL_Exported_Functions_Group2 + * @{ + */ +/* Peripheral Control functions ************************************************/ +void HAL_IncTick(void); +void HAL_Delay(__IO uint32_t Delay); +uint32_t HAL_GetTick(void); +void HAL_SuspendTick(void); +void HAL_ResumeTick(void); +uint32_t HAL_GetHalVersion(void); +uint32_t HAL_GetREVID(void); +uint32_t HAL_GetDEVID(void); +void HAL_DBGMCU_EnableDBGSleepMode(void); +void HAL_DBGMCU_DisableDBGSleepMode(void); +void HAL_DBGMCU_EnableDBGStopMode(void); +void HAL_DBGMCU_DisableDBGStopMode(void); +void HAL_DBGMCU_EnableDBGStandbyMode(void); +void HAL_DBGMCU_DisableDBGStandbyMode(void); +void HAL_EnableCompensationCell(void); +void HAL_DisableCompensationCell(void); +void HAL_EnableFMCMemorySwapping(void); +void HAL_DisableFMCMemorySwapping(void); +#if defined (STM32F765xx) || defined (STM32F767xx) || defined (STM32F769xx) || defined (STM32F777xx) || defined (STM32F779xx) +void HAL_EnableMemorySwappingBank(void); +void HAL_DisableMemorySwappingBank(void); +#endif /* STM32F765xx || STM32F767xx || STM32F769xx || STM32F777xx || STM32F779xx */ +/** + * @} + */ + +/** + * @} + */ +/* Private types -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/** @defgroup HAL_Private_Variables HAL Private Variables + * @{ + */ +/** + * @} + */ +/* Private constants ---------------------------------------------------------*/ +/** @defgroup HAL_Private_Constants HAL Private Constants + * @{ + */ +/** + * @} + */ +/* Private macros ------------------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/** + * @} + */ + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F7xx_HAL_H */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/stm32f7xx_hal_conf.h Fri May 19 09:12:45 2017 +0000 @@ -0,0 +1,439 @@ +/** + ****************************************************************************** + * @file stm32f7xx_hal_conf.h + * @brief HAL configuration file. + ****************************************************************************** + * @attention + * + * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2> + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F7xx_HAL_CONF_H +#define __STM32F7xx_HAL_CONF_H + +#ifdef __cplusplus + extern "C" { +#endif + +#include "main.h" +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ +/** + * @brief This is the list of modules to be used in the HAL driver + */ +#define HAL_MODULE_ENABLED + +#define HAL_ADC_MODULE_ENABLED +/* #define HAL_CAN_MODULE_ENABLED */ +/* #define HAL_CEC_MODULE_ENABLED */ +/* #define HAL_CRC_MODULE_ENABLED */ +/* #define HAL_CRYP_MODULE_ENABLED */ +/* #define HAL_DAC_MODULE_ENABLED */ +/* #define HAL_DCMI_MODULE_ENABLED */ +/* #define HAL_DMA2D_MODULE_ENABLED */ +/* #define HAL_ETH_MODULE_ENABLED */ +/* #define HAL_NAND_MODULE_ENABLED */ +/* #define HAL_NOR_MODULE_ENABLED */ +/* #define HAL_SRAM_MODULE_ENABLED */ +/* #define HAL_SDRAM_MODULE_ENABLED */ +/* #define HAL_HASH_MODULE_ENABLED */ +/* #define HAL_I2S_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +/* #define HAL_LPTIM_MODULE_ENABLED */ +/* #define HAL_LTDC_MODULE_ENABLED */ +/* #define HAL_QSPI_MODULE_ENABLED */ +/* #define HAL_RNG_MODULE_ENABLED */ +/* #define HAL_RTC_MODULE_ENABLED */ +/* #define HAL_SAI_MODULE_ENABLED */ +/* #define HAL_SD_MODULE_ENABLED */ +/* #define HAL_SPDIFRX_MODULE_ENABLED */ +/* #define HAL_SPI_MODULE_ENABLED */ +#define HAL_TIM_MODULE_ENABLED +/* #define HAL_UART_MODULE_ENABLED */ +/* #define HAL_USART_MODULE_ENABLED */ +/* #define HAL_IRDA_MODULE_ENABLED */ +/* #define HAL_SMARTCARD_MODULE_ENABLED */ +/* #define HAL_WWDG_MODULE_ENABLED */ +/* #define HAL_PCD_MODULE_ENABLED */ +/* #define HAL_HCD_MODULE_ENABLED */ +/* #define HAL_DFSDM_MODULE_ENABLED */ +/* #define HAL_DSI_MODULE_ENABLED */ +/* #define HAL_JPEG_MODULE_ENABLED */ +/* #define HAL_MDIOS_MODULE_ENABLED */ +#define HAL_GPIO_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +#define HAL_FLASH_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED + +/* ########################## HSE/HSI Values adaptation ##################### */ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE ((uint32_t)16000000U) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) + #define LSI_VALUE ((uint32_t)32000U) /*!< LSI Typical Value in Hz*/ +#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz + The real value may vary depending on the variations + in voltage and temperature. */ +/** + * @brief External Low Speed oscillator (LSE) value. + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE ((uint32_t)32768U) /*!< Value of the External Low Speed oscillator in Hz */ +#endif /* LSE_VALUE */ + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT ((uint32_t)5000U) /*!< Time out for LSE start up, in ms */ +#endif /* LSE_STARTUP_TIMEOUT */ + +/** + * @brief External clock source for I2S peripheral + * This value is used by the I2S HAL module to compute the I2S clock source + * frequency, this source is inserted directly through I2S_CKIN pad. + */ +#if !defined (EXTERNAL_CLOCK_VALUE) + #define EXTERNAL_CLOCK_VALUE ((uint32_t)12288000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* EXTERNAL_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#define VDD_VALUE ((uint32_t)3300U) /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY ((uint32_t)0U) /*!< tick interrupt priority */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 0U +#define ART_ACCLERATOR_ENABLE 0U /* To enable instruction cache and prefetch */ + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1 */ + +/* ################## Ethernet peripheral configuration ##################### */ + +/* Section 1 : Ethernet peripheral configuration */ + +/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */ +#define MAC_ADDR0 2U +#define MAC_ADDR1 0U +#define MAC_ADDR2 0U +#define MAC_ADDR3 0U +#define MAC_ADDR4 0U +#define MAC_ADDR5 0U + +/* Definition of the Ethernet driver buffers size and count */ +#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */ +#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */ +#define ETH_RXBUFNB ((uint32_t)4U) /* 4 Rx buffers of size ETH_RX_BUF_SIZE */ +#define ETH_TXBUFNB ((uint32_t)4U) /* 4 Tx buffers of size ETH_TX_BUF_SIZE */ + +/* Section 2: PHY configuration section */ + +/* DP83848_PHY_ADDRESS Address*/ +#define DP83848_PHY_ADDRESS 0x01U +/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ +#define PHY_RESET_DELAY ((uint32_t)0x000000FFU) +/* PHY Configuration delay */ +#define PHY_CONFIG_DELAY ((uint32_t)0x00000FFFU) + +#define PHY_READ_TO ((uint32_t)0x0000FFFFU) +#define PHY_WRITE_TO ((uint32_t)0x0000FFFFU) + +/* Section 3: Common PHY Registers */ + +#define PHY_BCR ((uint16_t)0x0000U) /*!< Transceiver Basic Control Register */ +#define PHY_BSR ((uint16_t)0x0001U) /*!< Transceiver Basic Status Register */ + +#define PHY_RESET ((uint16_t)0x8000U) /*!< PHY Reset */ +#define PHY_LOOPBACK ((uint16_t)0x4000U) /*!< Select loop-back mode */ +#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100U) /*!< Set the full-duplex mode at 100 Mb/s */ +#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000U) /*!< Set the half-duplex mode at 100 Mb/s */ +#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100U) /*!< Set the full-duplex mode at 10 Mb/s */ +#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000U) /*!< Set the half-duplex mode at 10 Mb/s */ +#define PHY_AUTONEGOTIATION ((uint16_t)0x1000U) /*!< Enable auto-negotiation function */ +#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200U) /*!< Restart auto-negotiation function */ +#define PHY_POWERDOWN ((uint16_t)0x0800U) /*!< Select the power down mode */ +#define PHY_ISOLATE ((uint16_t)0x0400U) /*!< Isolate PHY from MII */ + +#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020U) /*!< Auto-Negotiation process completed */ +#define PHY_LINKED_STATUS ((uint16_t)0x0004U) /*!< Valid link established */ +#define PHY_JABBER_DETECTION ((uint16_t)0x0002U) /*!< Jabber condition detected */ + +/* Section 4: Extended PHY Registers */ +#define PHY_SR ((uint16_t)0x10U) /*!< PHY status register Offset */ + +#define PHY_SPEED_STATUS ((uint16_t)0x0002U) /*!< PHY Speed mask */ +#define PHY_DUPLEX_STATUS ((uint16_t)0x0004U) /*!< PHY Duplex mask */ + +/* ################## SPI peripheral configuration ########################## */ + +/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver +* Activated: CRC code is present inside driver +* Deactivated: CRC code cleaned from driver +*/ + +#define USE_SPI_CRC 0U + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32f7xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32f7xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32f7xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32f7xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32f7xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32f7xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED + #include "stm32f7xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32f7xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "stm32f7xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED + #include "stm32f7xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32f7xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED + #include "stm32f7xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED + #include "stm32f7xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32f7xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32f7xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32f7xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32f7xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_SDRAM_MODULE_ENABLED + #include "stm32f7xx_hal_sdram.h" +#endif /* HAL_SDRAM_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED + #include "stm32f7xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32f7xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32f7xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32f7xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED + #include "stm32f7xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED + #include "stm32f7xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32f7xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED + #include "stm32f7xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "stm32f7xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32f7xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "stm32f7xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32f7xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SPDIFRX_MODULE_ENABLED + #include "stm32f7xx_hal_spdifrx.h" +#endif /* HAL_SPDIFRX_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32f7xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32f7xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32f7xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32f7xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32f7xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32f7xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32f7xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32f7xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32f7xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED + #include "stm32f7xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_DSI_MODULE_ENABLED + #include "stm32f7xx_hal_dsi.h" +#endif /* HAL_DSI_MODULE_ENABLED */ + +#ifdef HAL_JPEG_MODULE_ENABLED + #include "stm32f7xx_hal_jpeg.h" +#endif /* HAL_JPEG_MODULE_ENABLED */ + +#ifdef HAL_MDIOS_MODULE_ENABLED + #include "stm32f7xx_hal_mdios.h" +#endif /* HAL_MDIOS_MODULE_ENABLED */ +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F7xx_HAL_CONF_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/stm32f7xx_hal_msp.c Fri May 19 09:12:45 2017 +0000 @@ -0,0 +1,340 @@ +/** + ****************************************************************************** + * File Name : stm32f7xx_hal_msp.c + * Description : This file provides code for the MSP Initialization + * and de-Initialization codes. + ****************************************************************************** + * + * COPYRIGHT(c) 2017 STMicroelectronics + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ +/* Includes ------------------------------------------------------------------*/ +#include "stm32f7xx_hal.h" + +extern DMA_HandleTypeDef hdma_adc2; + +extern void Error_Handler(void); +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ +/** + * Initializes the Global MSP. + */ +void HAL_MspInit(void) +{ + /* USER CODE BEGIN MspInit 0 */ + + /* USER CODE END MspInit 0 */ + + HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4); + + /* System interrupt init*/ + /* MemoryManagement_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(MemoryManagement_IRQn, 0, 0); + /* BusFault_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(BusFault_IRQn, 0, 0); + /* UsageFault_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(UsageFault_IRQn, 0, 0); + /* SVCall_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(SVCall_IRQn, 0, 0); + /* DebugMonitor_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(DebugMonitor_IRQn, 0, 0); + /* PendSV_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(PendSV_IRQn, 0, 0); + /* SysTick_IRQn interrupt configuration */ + HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); + + /* USER CODE BEGIN MspInit 1 */ + + /* USER CODE END MspInit 1 */ +} + +void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc) +{ + + GPIO_InitTypeDef GPIO_InitStruct; + if(hadc->Instance==ADC2) + { + /* USER CODE BEGIN ADC2_MspInit 0 */ + + /* USER CODE END ADC2_MspInit 0 */ + /* Peripheral clock enable */ + __HAL_RCC_ADC2_CLK_ENABLE(); + + /**ADC2 GPIO Configuration + PA5 ------> ADC2_IN5 + PA6 ------> ADC2_IN6 + */ + GPIO_InitStruct.Pin = GPIO_PIN_5|GPIO_PIN_6; + GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Peripheral DMA init*/ + + hdma_adc2.Instance = DMA2_Stream2; + hdma_adc2.Init.Channel = DMA_CHANNEL_1; + hdma_adc2.Init.Direction = DMA_PERIPH_TO_MEMORY; + hdma_adc2.Init.PeriphInc = DMA_PINC_DISABLE; + hdma_adc2.Init.MemInc = DMA_MINC_ENABLE; + hdma_adc2.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + hdma_adc2.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; + hdma_adc2.Init.Mode = DMA_CIRCULAR; + hdma_adc2.Init.Priority = DMA_PRIORITY_LOW; + hdma_adc2.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + if (HAL_DMA_Init(&hdma_adc2) != HAL_OK) + { + Error_Handler(); + } + + __HAL_LINKDMA(hadc,DMA_Handle,hdma_adc2); + + /* USER CODE BEGIN ADC2_MspInit 1 */ + + /* USER CODE END ADC2_MspInit 1 */ + } + +} + +void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc) +{ + + if(hadc->Instance==ADC2) + { + /* USER CODE BEGIN ADC2_MspDeInit 0 */ + + /* USER CODE END ADC2_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_ADC2_CLK_DISABLE(); + + /**ADC2 GPIO Configuration + PA5 ------> ADC2_IN5 + PA6 ------> ADC2_IN6 + */ + HAL_GPIO_DeInit(GPIOA, GPIO_PIN_5|GPIO_PIN_6); + + /* Peripheral DMA DeInit*/ + HAL_DMA_DeInit(hadc->DMA_Handle); + } + /* USER CODE BEGIN ADC2_MspDeInit 1 */ + + /* USER CODE END ADC2_MspDeInit 1 */ + +} + +void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef* htim_encoder) +{ + + GPIO_InitTypeDef GPIO_InitStruct; + if(htim_encoder->Instance==TIM1) + { + /* USER CODE BEGIN TIM1_MspInit 0 */ + + /* USER CODE END TIM1_MspInit 0 */ + /* Peripheral clock enable */ + __HAL_RCC_TIM1_CLK_ENABLE(); + + /**TIM1 GPIO Configuration + PE9 ------> TIM1_CH1 + PE11 ------> TIM1_CH2 + */ + GPIO_InitStruct.Pin = GPIO_PIN_9; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + GPIO_InitStruct.Alternate = GPIO_AF1_TIM1; + HAL_GPIO_Init(GPIOE, &GPIO_InitStruct); + + GPIO_InitStruct.Pin = GPIO_PIN_11; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + GPIO_InitStruct.Alternate = GPIO_AF1_TIM1; + HAL_GPIO_Init(GPIOE, &GPIO_InitStruct); + + /* USER CODE BEGIN TIM1_MspInit 1 */ + + /* USER CODE END TIM1_MspInit 1 */ + } + else if(htim_encoder->Instance==TIM4) + { + /* USER CODE BEGIN TIM4_MspInit 0 */ + + /* USER CODE END TIM4_MspInit 0 */ + /* Peripheral clock enable */ + __HAL_RCC_TIM4_CLK_ENABLE(); + + /**TIM4 GPIO Configuration + PD12 ------> TIM4_CH1 + PD13 ------> TIM4_CH2 + */ + GPIO_InitStruct.Pin = GPIO_PIN_12; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + GPIO_InitStruct.Alternate = GPIO_AF2_TIM4; + HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); + + GPIO_InitStruct.Pin = GPIO_PIN_13; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + GPIO_InitStruct.Alternate = GPIO_AF2_TIM4; + HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); + + /* USER CODE BEGIN TIM4_MspInit 1 */ + + /* USER CODE END TIM4_MspInit 1 */ + } + +} + +void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef* htim_pwm) +{ + + if(htim_pwm->Instance==TIM9) + { + /* USER CODE BEGIN TIM9_MspInit 0 */ + + /* USER CODE END TIM9_MspInit 0 */ + /* Peripheral clock enable */ + __HAL_RCC_TIM9_CLK_ENABLE(); + /* USER CODE BEGIN TIM9_MspInit 1 */ + + /* USER CODE END TIM9_MspInit 1 */ + } + +} + +void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim) +{ + + GPIO_InitTypeDef GPIO_InitStruct; + if(htim->Instance==TIM9) + { + /* USER CODE BEGIN TIM9_MspPostInit 0 */ + + /* USER CODE END TIM9_MspPostInit 0 */ + + /**TIM9 GPIO Configuration + PE5 ------> TIM9_CH1 + PE6 ------> TIM9_CH2 + */ + GPIO_InitStruct.Pin = GPIO_PIN_5|GPIO_PIN_6; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; + GPIO_InitStruct.Alternate = GPIO_AF3_TIM9; + HAL_GPIO_Init(GPIOE, &GPIO_InitStruct); + + /* USER CODE BEGIN TIM9_MspPostInit 1 */ + + /* USER CODE END TIM9_MspPostInit 1 */ + } + +} + +void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef* htim_encoder) +{ + + if(htim_encoder->Instance==TIM1) + { + /* USER CODE BEGIN TIM1_MspDeInit 0 */ + + /* USER CODE END TIM1_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_TIM1_CLK_DISABLE(); + + /**TIM1 GPIO Configuration + PE9 ------> TIM1_CH1 + PE11 ------> TIM1_CH2 + */ + HAL_GPIO_DeInit(GPIOE, GPIO_PIN_9|GPIO_PIN_11); + + /* USER CODE BEGIN TIM1_MspDeInit 1 */ + + /* USER CODE END TIM1_MspDeInit 1 */ + } + else if(htim_encoder->Instance==TIM4) + { + /* USER CODE BEGIN TIM4_MspDeInit 0 */ + + /* USER CODE END TIM4_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_TIM4_CLK_DISABLE(); + + /**TIM4 GPIO Configuration + PD12 ------> TIM4_CH1 + PD13 ------> TIM4_CH2 + */ + HAL_GPIO_DeInit(GPIOD, GPIO_PIN_12|GPIO_PIN_13); + + /* USER CODE BEGIN TIM4_MspDeInit 1 */ + + /* USER CODE END TIM4_MspDeInit 1 */ + } + +} + +void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef* htim_pwm) +{ + + if(htim_pwm->Instance==TIM9) + { + /* USER CODE BEGIN TIM9_MspDeInit 0 */ + + /* USER CODE END TIM9_MspDeInit 0 */ + /* Peripheral clock disable */ + __HAL_RCC_TIM9_CLK_DISABLE(); + } + /* USER CODE BEGIN TIM9_MspDeInit 1 */ + + /* USER CODE END TIM9_MspDeInit 1 */ + +} + +/* USER CODE BEGIN 1 */ +void Error_Handler(void) +{ + /* USER CODE BEGIN Error_Handler */ + /* User can add his own implementation to report the HAL error return state */ + while(1) + { + } + /* USER CODE END Error_Handler */ +} +/* USER CODE END 1 */ + +/** + * @} + */ + +/** + * @} + */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/stm32f7xx_it.c Fri May 19 09:12:45 2017 +0000 @@ -0,0 +1,79 @@ +/** + ****************************************************************************** + * @file stm32f7xx_it.c + * @brief Interrupt Service Routines. + ****************************************************************************** + * + * COPYRIGHT(c) 2017 STMicroelectronics + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ +/* Includes ------------------------------------------------------------------*/ +#include "stm32f7xx_hal.h" +#include "stm32f7xx.h" +#include "stm32f7xx_it.h" + +/* USER CODE BEGIN 0 */ + +/* USER CODE END 0 */ + +/* External variables --------------------------------------------------------*/ +extern DMA_HandleTypeDef hdma_adc2; + +/******************************************************************************/ +/* Cortex-M7 Processor Interruption and Exception Handlers */ +/******************************************************************************/ + +/** +* @brief This function handles System service call via SWI instruction. +*/ + + +/******************************************************************************/ +/* STM32F7xx Peripheral Interrupt Handlers */ +/* Add here the Interrupt Handlers for the used peripherals. */ +/* For the available peripheral interrupt handler names, */ +/* please refer to the startup file (startup_stm32f7xx.s). */ +/******************************************************************************/ + +/** +* @brief This function handles DMA2 stream2 global interrupt. +*/ +void DMA2_Stream2_IRQHandler(void) +{ + /* USER CODE BEGIN DMA2_Stream2_IRQn 0 */ + + /* USER CODE END DMA2_Stream2_IRQn 0 */ + HAL_DMA_IRQHandler(&hdma_adc2); + /* USER CODE BEGIN DMA2_Stream2_IRQn 1 */ + + /* USER CODE END DMA2_Stream2_IRQn 1 */ +} + +/* USER CODE BEGIN 1 */ + +/* USER CODE END 1 */ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/stm32f7xx_it.h Fri May 19 09:12:45 2017 +0000 @@ -0,0 +1,60 @@ +/** + ****************************************************************************** + * @file stm32f7xx_it.h + * @brief This file contains the headers of the interrupt handlers. + ****************************************************************************** + * + * COPYRIGHT(c) 2017 STMicroelectronics + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F7xx_IT_H +#define __STM32F7xx_IT_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +void SVC_Handler(void); +void PendSV_Handler(void); +void SysTick_Handler(void); +void DMA2_Stream2_IRQHandler(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F7xx_IT_H */ + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ +