Merge pull request #11494 from haslinghuis/dshot_gpio
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F30x_StdPeriph_Driver / src / stm32f30x_crc.c
blob94a02fe33003dd87740eea06c948e38ffd34011e
1 /**
2 ******************************************************************************
3 * @file stm32f30x_crc.c
4 * @author MCD Application Team
5 * @version V1.1.1
6 * @date 04-April-2014
7 * @brief This file provides firmware functions to manage the following
8 * functionalities of CRC computation unit peripheral:
9 * + Configuration of the CRC computation unit
10 * + CRC computation of one/many 32-bit data
11 * + CRC Independent register (IDR) access
13 @verbatim
15 ===============================================================================
16 ##### How to use this driver #####
17 ===============================================================================
18 [..]
19 (#) Enable CRC AHB clock using RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE)
20 function.
21 (#) Select the polynomial size: 7-bit, 8-bit, 16-bit or 32-bit.
22 (#) Set the polynomial coefficients using CRC_SetPolynomial();
23 (#) If required, select the reverse operation on input data
24 using CRC_ReverseInputDataSelect();
25 (#) If required, enable the reverse operation on output data
26 using CRC_ReverseOutputDataCmd(Enable);
27 (#) If required, set the initialization remainder value using
28 CRC_SetInitRegister();
29 (#) use CRC_CalcCRC() function to compute the CRC of a 32-bit data
30 or use CRC_CalcBlockCRC() function to compute the CRC if a 32-bit
31 data buffer.
33 @endverbatim
35 ******************************************************************************
36 * @attention
38 * <h2><center>&copy; COPYRIGHT 2014 STMicroelectronics</center></h2>
40 * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
41 * You may not use this file except in compliance with the License.
42 * You may obtain a copy of the License at:
44 * http://www.st.com/software_license_agreement_liberty_v2
46 * Unless required by applicable law or agreed to in writing, software
47 * distributed under the License is distributed on an "AS IS" BASIS,
48 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
49 * See the License for the specific language governing permissions and
50 * limitations under the License.
52 ******************************************************************************
55 /* Includes ------------------------------------------------------------------*/
56 #include "stm32f30x_crc.h"
58 /** @addtogroup STM32F30x_StdPeriph_Driver
59 * @{
62 /** @defgroup CRC
63 * @brief CRC driver modules
64 * @{
67 /* Private typedef -----------------------------------------------------------*/
68 /* Private define ------------------------------------------------------------*/
69 /* Private macro -------------------------------------------------------------*/
70 /* Private variables ---------------------------------------------------------*/
71 /* Private function prototypes -----------------------------------------------*/
72 /* Private functions ---------------------------------------------------------*/
74 /** @defgroup CRC_Private_Functions
75 * @{
78 /** @defgroup CRC_Group1 Configuration of the CRC computation unit functions
79 * @brief Configuration of the CRC computation unit functions
81 @verbatim
82 ===============================================================================
83 ##### CRC configuration functions #####
84 ===============================================================================
86 @endverbatim
87 * @{
90 /**
91 * @brief Deinitializes CRC peripheral registers to their default reset values.
92 * @param None
93 * @retval None
95 void CRC_DeInit(void)
97 /* Set DR register to reset value */
98 CRC->DR = 0xFFFFFFFF;
99 /* Set the POL register to the reset value: 0x04C11DB7 */
100 CRC->POL = 0x04C11DB7;
101 /* Reset IDR register */
102 CRC->IDR = 0x00;
103 /* Set INIT register to reset value */
104 CRC->INIT = 0xFFFFFFFF;
105 /* Reset the CRC calculation unit */
106 CRC->CR = CRC_CR_RESET;
110 * @brief Resets the CRC calculation unit and sets INIT register content in DR register.
111 * @param None
112 * @retval None
114 void CRC_ResetDR(void)
116 /* Reset CRC generator */
117 CRC->CR |= CRC_CR_RESET;
121 * @brief Selects the polynomial size.
122 * @param CRC_PolSize: Specifies the polynomial size.
123 * This parameter can be:
124 * @arg CRC_PolSize_7: 7-bit polynomial for CRC calculation
125 * @arg CRC_PolSize_8: 8-bit polynomial for CRC calculation
126 * @arg CRC_PolSize_16: 16-bit polynomial for CRC calculation
127 * @arg CRC_PolSize_32: 32-bit polynomial for CRC calculation
128 * @retval None
130 void CRC_PolynomialSizeSelect(uint32_t CRC_PolSize)
132 uint32_t tmpcr = 0;
134 /* Check the parameter */
135 assert_param(IS_CRC_POL_SIZE(CRC_PolSize));
137 /* Get CR register value */
138 tmpcr = CRC->CR;
140 /* Reset POL_SIZE bits */
141 tmpcr &= (uint32_t)~((uint32_t)CRC_CR_POLSIZE);
142 /* Set the polynomial size */
143 tmpcr |= (uint32_t)CRC_PolSize;
145 /* Write to CR register */
146 CRC->CR = (uint32_t)tmpcr;
150 * @brief Selects the reverse operation to be performed on input data.
151 * @param CRC_ReverseInputData: Specifies the reverse operation on input data.
152 * This parameter can be:
153 * @arg CRC_ReverseInputData_No: No reverse operation is performed
154 * @arg CRC_ReverseInputData_8bits: reverse operation performed on 8 bits
155 * @arg CRC_ReverseInputData_16bits: reverse operation performed on 16 bits
156 * @arg CRC_ReverseInputData_32bits: reverse operation performed on 32 bits
157 * @retval None
159 void CRC_ReverseInputDataSelect(uint32_t CRC_ReverseInputData)
161 uint32_t tmpcr = 0;
163 /* Check the parameter */
164 assert_param(IS_CRC_REVERSE_INPUT_DATA(CRC_ReverseInputData));
166 /* Get CR register value */
167 tmpcr = CRC->CR;
169 /* Reset REV_IN bits */
170 tmpcr &= (uint32_t)~((uint32_t)CRC_CR_REV_IN);
171 /* Set the reverse operation */
172 tmpcr |= (uint32_t)CRC_ReverseInputData;
174 /* Write to CR register */
175 CRC->CR = (uint32_t)tmpcr;
179 * @brief Enables or disable the reverse operation on output data.
180 * The reverse operation on output data is performed on 32-bit.
181 * @param NewState: new state of the reverse operation on output data.
182 * This parameter can be: ENABLE or DISABLE.
183 * @retval None
185 void CRC_ReverseOutputDataCmd(FunctionalState NewState)
187 /* Check the parameters */
188 assert_param(IS_FUNCTIONAL_STATE(NewState));
190 if (NewState != DISABLE)
192 /* Enable reverse operation on output data */
193 CRC->CR |= CRC_CR_REV_OUT;
195 else
197 /* Disable reverse operation on output data */
198 CRC->CR &= (uint32_t)~((uint32_t)CRC_CR_REV_OUT);
203 * @brief Initializes the INIT register.
204 * @note After resetting CRC calculation unit, CRC_InitValue is stored in DR register
205 * @param CRC_InitValue: Programmable initial CRC value
206 * @retval None
208 void CRC_SetInitRegister(uint32_t CRC_InitValue)
210 CRC->INIT = CRC_InitValue;
214 * @brief Initializes the polynomail coefficients.
215 * @param CRC_Pol: Polynomial to be used for CRC calculation.
216 * @retval None
218 void CRC_SetPolynomial(uint32_t CRC_Pol)
220 CRC->POL = CRC_Pol;
224 * @}
227 /** @defgroup CRC_Group2 CRC computation of one/many 32-bit data functions
228 * @brief CRC computation of one/many 32-bit data functions
230 @verbatim
231 ===============================================================================
232 ##### CRC computation functions #####
233 ===============================================================================
235 @endverbatim
236 * @{
240 * @brief Computes the 32-bit CRC of a given data word(32-bit).
241 * @param CRC_Data: data word(32-bit) to compute its CRC
242 * @retval 32-bit CRC
244 uint32_t CRC_CalcCRC(uint32_t CRC_Data)
246 CRC->DR = CRC_Data;
248 return (CRC->DR);
252 * @brief Computes the 16-bit CRC of a given 16-bit data.
253 * @param CRC_Data: data half-word(16-bit) to compute its CRC
254 * @retval 16-bit CRC
256 uint32_t CRC_CalcCRC16bits(uint16_t CRC_Data)
258 *(uint16_t*)(CRC_BASE) = (uint16_t) CRC_Data;
260 return (CRC->DR);
264 * @brief Computes the 8-bit CRC of a given 8-bit data.
265 * @param CRC_Data: 8-bit data to compute its CRC
266 * @retval 8-bit CRC
268 uint32_t CRC_CalcCRC8bits(uint8_t CRC_Data)
270 *(uint8_t*)(CRC_BASE) = (uint8_t) CRC_Data;
272 return (CRC->DR);
276 * @brief Computes the 32-bit CRC of a given buffer of data word(32-bit).
277 * @param pBuffer: pointer to the buffer containing the data to be computed
278 * @param BufferLength: length of the buffer to be computed
279 * @retval 32-bit CRC
281 uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength)
283 uint32_t index = 0;
285 for(index = 0; index < BufferLength; index++)
287 CRC->DR = pBuffer[index];
289 return (CRC->DR);
293 * @brief Returns the current CRC value.
294 * @param None
295 * @retval 32-bit CRC
297 uint32_t CRC_GetCRC(void)
299 return (CRC->DR);
303 * @}
306 /** @defgroup CRC_Group3 CRC Independent Register (IDR) access functions
307 * @brief CRC Independent Register (IDR) access (write/read) functions
309 @verbatim
310 ===============================================================================
311 ##### CRC Independent Register (IDR) access functions #####
312 ===============================================================================
314 @endverbatim
315 * @{
319 * @brief Stores an 8-bit data in the Independent Data(ID) register.
320 * @param CRC_IDValue: 8-bit value to be stored in the ID register
321 * @retval None
323 void CRC_SetIDRegister(uint8_t CRC_IDValue)
325 CRC->IDR = CRC_IDValue;
329 * @brief Returns the 8-bit data stored in the Independent Data(ID) register
330 * @param None
331 * @retval 8-bit value of the ID register
333 uint8_t CRC_GetIDRegister(void)
335 return (CRC->IDR);
339 * @}
343 * @}
347 * @}
351 * @}
354 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/