2 ******************************************************************************
3 * @file stm32f4xx_hal_hash.c
4 * @author MCD Application Team
7 * @brief HASH HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the HASH peripheral:
10 * + Initialization and de-initialization functions
11 * + HASH/HMAC Processing functions by algorithm using polling mode
12 * + HASH/HMAC functions by algorithm using interrupt mode
13 * + HASH/HMAC functions by algorithm using DMA mode
14 * + Peripheral State functions
17 ==============================================================================
18 ##### How to use this driver #####
19 ==============================================================================
21 The HASH HAL driver can be used as follows:
22 (#)Initialize the HASH low level resources by implementing the HAL_HASH_MspInit():
23 (##) Enable the HASH interface clock using __HAL_RCC_HASH_CLK_ENABLE()
24 (##) In case of using processing APIs based on interrupts (e.g. HAL_HMAC_SHA1_Start_IT())
25 (+++) Configure the HASH interrupt priority using HAL_NVIC_SetPriority()
26 (+++) Enable the HASH IRQ handler using HAL_NVIC_EnableIRQ()
27 (+++) In HASH IRQ handler, call HAL_HASH_IRQHandler()
28 (##) In case of using DMA to control data transfer (e.g. HAL_HMAC_SHA1_Start_DMA())
29 (+++) Enable the DMAx interface clock using __DMAx_CLK_ENABLE()
30 (+++) Configure and enable one DMA stream one for managing data transfer from
31 memory to peripheral (input stream). Managing data transfer from
32 peripheral to memory can be performed only using CPU
33 (+++) Associate the initialized DMA handle to the HASH DMA handle
35 (+++) Configure the priority and enable the NVIC for the transfer complete
36 interrupt on the DMA Stream using HAL_NVIC_SetPriority() and HAL_NVIC_EnableIRQ()
37 (#)Initialize the HASH HAL using HAL_HASH_Init(). This function configures mainly:
38 (##) The data type: 1-bit, 8-bit, 16-bit and 32-bit.
39 (##) For HMAC, the encryption key.
40 (##) For HMAC, the key size used for encryption.
41 (#)Three processing functions are available:
42 (##) Polling mode: processing APIs are blocking functions
43 i.e. they process the data and wait till the digest computation is finished
44 e.g. HAL_HASH_SHA1_Start()
45 (##) Interrupt mode: encryption and decryption APIs are not blocking functions
46 i.e. they process the data under interrupt
47 e.g. HAL_HASH_SHA1_Start_IT()
48 (##) DMA mode: processing APIs are not blocking functions and the CPU is
49 not used for data transfer i.e. the data transfer is ensured by DMA
50 e.g. HAL_HASH_SHA1_Start_DMA()
51 (#)When the processing function is called at first time after HAL_HASH_Init()
52 the HASH peripheral is initialized and processes the buffer in input.
53 After that, the digest computation is started.
54 When processing multi-buffer use the accumulate function to write the
55 data in the peripheral without starting the digest computation. In last
56 buffer use the start function to input the last buffer ans start the digest
58 (##) e.g. HAL_HASH_SHA1_Accumulate() : write 1st data buffer in the peripheral without starting the digest computation
59 (##) write (n-1)th data buffer in the peripheral without starting the digest computation
60 (##) HAL_HASH_SHA1_Start() : write (n)th data buffer in the peripheral and start the digest computation
61 (#)In HMAC mode, there is no Accumulate API. Only Start API is available.
62 (#)In case of using DMA, call the DMA start processing e.g. HAL_HASH_SHA1_Start_DMA().
63 After that, call the finish function in order to get the digest value
64 e.g. HAL_HASH_SHA1_Finish()
65 (#)Call HAL_HASH_DeInit() to deinitialize the HASH peripheral.
68 ******************************************************************************
71 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
73 * Redistribution and use in source and binary forms, with or without modification,
74 * are permitted provided that the following conditions are met:
75 * 1. Redistributions of source code must retain the above copyright notice,
76 * this list of conditions and the following disclaimer.
77 * 2. Redistributions in binary form must reproduce the above copyright notice,
78 * this list of conditions and the following disclaimer in the documentation
79 * and/or other materials provided with the distribution.
80 * 3. Neither the name of STMicroelectronics nor the names of its contributors
81 * may be used to endorse or promote products derived from this software
82 * without specific prior written permission.
84 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
85 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
86 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
87 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
88 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
89 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
90 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
91 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
92 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
93 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
95 ******************************************************************************
98 /* Includes ------------------------------------------------------------------*/
99 #include "stm32f4xx_hal.h"
101 /** @addtogroup STM32F4xx_HAL_Driver
105 /** @defgroup HASH HASH
106 * @brief HASH HAL module driver.
110 #ifdef HAL_HASH_MODULE_ENABLED
112 #if defined(STM32F415xx) || defined(STM32F417xx) || defined(STM32F437xx) || defined(STM32F439xx) || defined(STM32F479xx)
114 /* Private typedef -----------------------------------------------------------*/
115 /* Private define ------------------------------------------------------------*/
116 /* Private macro -------------------------------------------------------------*/
117 /* Private variables ---------------------------------------------------------*/
118 /* Private function prototypes -----------------------------------------------*/
119 /** @defgroup HASH_Private_Functions HASH Private Functions
122 static void HASH_DMAXferCplt(DMA_HandleTypeDef
*hdma
);
123 static void HASH_DMAError(DMA_HandleTypeDef
*hdma
);
124 static void HASH_GetDigest(uint8_t *pMsgDigest
, uint8_t Size
);
125 static void HASH_WriteData(uint8_t *pInBuffer
, uint32_t Size
);
130 /* Private functions ---------------------------------------------------------*/
131 /** @addtogroup HASH_Private_Functions
136 * @brief DMA HASH Input Data complete callback.
137 * @param hdma: DMA handle
140 static void HASH_DMAXferCplt(DMA_HandleTypeDef
*hdma
)
142 HASH_HandleTypeDef
* hhash
= ( HASH_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
143 uint32_t inputaddr
= 0U;
144 uint32_t buffersize
= 0U;
146 if((HASH
->CR
& HASH_CR_MODE
) != HASH_CR_MODE
)
148 /* Disable the DMA transfer */
149 HASH
->CR
&= (uint32_t)(~HASH_CR_DMAE
);
151 /* Change HASH peripheral state */
152 hhash
->State
= HAL_HASH_STATE_READY
;
154 /* Call Input data transfer complete callback */
155 HAL_HASH_InCpltCallback(hhash
);
159 /* Increment Interrupt counter */
160 hhash
->HashInCount
++;
161 /* Disable the DMA transfer before starting the next transfer */
162 HASH
->CR
&= (uint32_t)(~HASH_CR_DMAE
);
164 if(hhash
->HashInCount
<= 2U)
166 /* In case HashInCount = 1, set the DMA to transfer data to HASH DIN register */
167 if(hhash
->HashInCount
== 1U)
169 inputaddr
= (uint32_t)hhash
->pHashInBuffPtr
;
170 buffersize
= hhash
->HashBuffSize
;
172 /* In case HashInCount = 2, set the DMA to transfer key to HASH DIN register */
173 else if(hhash
->HashInCount
== 2U)
175 inputaddr
= (uint32_t)hhash
->Init
.pKey
;
176 buffersize
= hhash
->Init
.KeySize
;
178 /* Configure the number of valid bits in last word of the message */
179 MODIFY_REG(HASH
->STR
, HASH_STR_NBLW
, 8U * (buffersize
% 4U));
181 /* Set the HASH DMA transfer complete */
182 hhash
->hdmain
->XferCpltCallback
= HASH_DMAXferCplt
;
184 /* Enable the DMA In DMA Stream */
185 HAL_DMA_Start_IT(hhash
->hdmain
, inputaddr
, (uint32_t)&HASH
->DIN
, (buffersize
%4U ? (buffersize
+3U)/4U:buffersize
/4U));
187 /* Enable DMA requests */
188 HASH
->CR
|= (HASH_CR_DMAE
);
192 /* Disable the DMA transfer */
193 HASH
->CR
&= (uint32_t)(~HASH_CR_DMAE
);
195 /* Reset the InCount */
196 hhash
->HashInCount
= 0U;
198 /* Change HASH peripheral state */
199 hhash
->State
= HAL_HASH_STATE_READY
;
201 /* Call Input data transfer complete callback */
202 HAL_HASH_InCpltCallback(hhash
);
208 * @brief DMA HASH communication error callback.
209 * @param hdma: DMA handle
212 static void HASH_DMAError(DMA_HandleTypeDef
*hdma
)
214 HASH_HandleTypeDef
* hhash
= ( HASH_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
215 hhash
->State
= HAL_HASH_STATE_READY
;
216 HAL_HASH_ErrorCallback(hhash
);
220 * @brief Writes the input buffer in data register.
221 * @param pInBuffer: Pointer to input buffer
222 * @param Size: The size of input buffer
225 static void HASH_WriteData(uint8_t *pInBuffer
, uint32_t Size
)
227 uint32_t buffercounter
;
228 uint32_t inputaddr
= (uint32_t) pInBuffer
;
230 for(buffercounter
= 0U; buffercounter
< Size
; buffercounter
+=4)
232 HASH
->DIN
= *(uint32_t*)inputaddr
;
238 * @brief Provides the message digest result.
239 * @param pMsgDigest: Pointer to the message digest
240 * @param Size: The size of the message digest in bytes
243 static void HASH_GetDigest(uint8_t *pMsgDigest
, uint8_t Size
)
245 uint32_t msgdigest
= (uint32_t)pMsgDigest
;
250 /* Read the message digest */
251 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[0U]);
253 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[1U]);
255 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[2U]);
257 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[3U]);
260 /* Read the message digest */
261 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[0U]);
263 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[1U]);
265 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[2U]);
267 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[3U]);
269 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[4U]);
272 /* Read the message digest */
273 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[0U]);
275 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[1U]);
277 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[2U]);
279 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[3U]);
281 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[4U]);
283 *(uint32_t*)(msgdigest
) = __REV(HASH_DIGEST
->HR
[5U]);
285 *(uint32_t*)(msgdigest
) = __REV(HASH_DIGEST
->HR
[6U]);
288 /* Read the message digest */
289 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[0U]);
291 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[1U]);
293 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[2U]);
295 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[3U]);
297 *(uint32_t*)(msgdigest
) = __REV(HASH
->HR
[4U]);
299 *(uint32_t*)(msgdigest
) = __REV(HASH_DIGEST
->HR
[5U]);
301 *(uint32_t*)(msgdigest
) = __REV(HASH_DIGEST
->HR
[6U]);
303 *(uint32_t*)(msgdigest
) = __REV(HASH_DIGEST
->HR
[7U]);
314 /* Exported functions --------------------------------------------------------*/
315 /** @addtogroup HASH_Exported_Functions
320 /** @addtogroup HASH_Exported_Functions_Group1 Initialization and de-initialization functions
321 * @brief Initialization and Configuration functions.
324 ===============================================================================
325 ##### Initialization and de-initialization functions #####
326 ===============================================================================
327 [..] This section provides functions allowing to:
328 (+) Initialize the HASH according to the specified parameters
329 in the HASH_InitTypeDef and creates the associated handle.
330 (+) DeInitialize the HASH peripheral.
331 (+) Initialize the HASH MSP.
332 (+) DeInitialize HASH MSP.
339 * @brief Initializes the HASH according to the specified parameters in the
340 HASH_HandleTypeDef and creates the associated handle.
341 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
342 * the configuration information for HASH module
345 HAL_StatusTypeDef
HAL_HASH_Init(HASH_HandleTypeDef
*hhash
)
347 /* Check the hash handle allocation */
353 /* Check the parameters */
354 assert_param(IS_HASH_DATATYPE(hhash
->Init
.DataType
));
356 if(hhash
->State
== HAL_HASH_STATE_RESET
)
358 /* Allocate lock resource and initialize it */
359 hhash
->Lock
= HAL_UNLOCKED
;
360 /* Init the low level hardware */
361 HAL_HASH_MspInit(hhash
);
364 /* Change the HASH state */
365 hhash
->State
= HAL_HASH_STATE_BUSY
;
367 /* Reset HashInCount, HashBuffSize and HashITCounter */
368 hhash
->HashInCount
= 0U;
369 hhash
->HashBuffSize
= 0U;
370 hhash
->HashITCounter
= 0U;
372 /* Set the data type */
373 HASH
->CR
|= (uint32_t) (hhash
->Init
.DataType
);
375 /* Change the HASH state */
376 hhash
->State
= HAL_HASH_STATE_READY
;
378 /* Set the default HASH phase */
379 hhash
->Phase
= HAL_HASH_PHASE_READY
;
381 /* Return function status */
386 * @brief DeInitializes the HASH peripheral.
387 * @note This API must be called before starting a new processing.
388 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
389 * the configuration information for HASH module
392 HAL_StatusTypeDef
HAL_HASH_DeInit(HASH_HandleTypeDef
*hhash
)
394 /* Check the HASH handle allocation */
400 /* Change the HASH state */
401 hhash
->State
= HAL_HASH_STATE_BUSY
;
403 /* Set the default HASH phase */
404 hhash
->Phase
= HAL_HASH_PHASE_READY
;
406 /* Reset HashInCount, HashBuffSize and HashITCounter */
407 hhash
->HashInCount
= 0U;
408 hhash
->HashBuffSize
= 0U;
409 hhash
->HashITCounter
= 0U;
411 /* DeInit the low level hardware */
412 HAL_HASH_MspDeInit(hhash
);
414 /* Change the HASH state */
415 hhash
->State
= HAL_HASH_STATE_RESET
;
420 /* Return function status */
425 * @brief Initializes the HASH MSP.
426 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
427 * the configuration information for HASH module
430 __weak
void HAL_HASH_MspInit(HASH_HandleTypeDef
*hhash
)
432 /* Prevent unused argument(s) compilation warning */
434 /* NOTE: This function Should not be modified, when the callback is needed,
435 the HAL_HASH_MspInit could be implemented in the user file
440 * @brief DeInitializes HASH MSP.
441 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
442 * the configuration information for HASH module
445 __weak
void HAL_HASH_MspDeInit(HASH_HandleTypeDef
*hhash
)
447 /* Prevent unused argument(s) compilation warning */
449 /* NOTE: This function Should not be modified, when the callback is needed,
450 the HAL_HASH_MspDeInit could be implemented in the user file
455 * @brief Input data transfer complete callback.
456 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
457 * the configuration information for HASH module
460 __weak
void HAL_HASH_InCpltCallback(HASH_HandleTypeDef
*hhash
)
462 /* Prevent unused argument(s) compilation warning */
464 /* NOTE: This function Should not be modified, when the callback is needed,
465 the HAL_HASH_InCpltCallback could be implemented in the user file
470 * @brief Data transfer Error callback.
471 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
472 * the configuration information for HASH module
475 __weak
void HAL_HASH_ErrorCallback(HASH_HandleTypeDef
*hhash
)
477 /* Prevent unused argument(s) compilation warning */
479 /* NOTE: This function Should not be modified, when the callback is needed,
480 the HAL_HASH_ErrorCallback could be implemented in the user file
485 * @brief Digest computation complete callback. It is used only with interrupt.
486 * @note This callback is not relevant with DMA.
487 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
488 * the configuration information for HASH module
491 __weak
void HAL_HASH_DgstCpltCallback(HASH_HandleTypeDef
*hhash
)
493 /* Prevent unused argument(s) compilation warning */
495 /* NOTE: This function Should not be modified, when the callback is needed,
496 the HAL_HASH_DgstCpltCallback could be implemented in the user file
504 /** @defgroup HASH_Exported_Functions_Group2 HASH processing functions using polling mode
505 * @brief processing functions using polling mode
508 ===============================================================================
509 ##### HASH processing using polling mode functions#####
510 ===============================================================================
511 [..] This section provides functions allowing to calculate in polling mode
512 the hash value using one of the following algorithms:
521 * @brief Initializes the HASH peripheral in MD5 mode then processes pInBuffer.
522 The digest is available in pOutBuffer.
523 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
524 * the configuration information for HASH module
525 * @param pInBuffer: Pointer to the input buffer (buffer to be hashed).
526 * @param Size: Length of the input buffer in bytes.
527 * If the Size is multiple of 64 bytes, appending the input buffer is possible.
528 * If the Size is not multiple of 64 bytes, the padding is managed by hardware
529 * and appending the input buffer is no more possible.
530 * @param pOutBuffer: Pointer to the computed digest. Its size must be 16 bytes.
531 * @param Timeout: Timeout value
534 HAL_StatusTypeDef
HAL_HASH_MD5_Start(HASH_HandleTypeDef
*hhash
, uint8_t *pInBuffer
, uint32_t Size
, uint8_t* pOutBuffer
, uint32_t Timeout
)
536 uint32_t tickstart
= 0U;
541 /* Change the HASH state */
542 hhash
->State
= HAL_HASH_STATE_BUSY
;
544 /* Check if initialization phase has already been performed */
545 if(hhash
->Phase
== HAL_HASH_PHASE_READY
)
547 /* Select the MD5 mode and reset the HASH processor core, so that the HASH will be ready to compute
548 the message digest of a new message */
549 HASH
->CR
|= HASH_ALGOSELECTION_MD5
| HASH_CR_INIT
;
553 hhash
->Phase
= HAL_HASH_PHASE_PROCESS
;
555 /* Configure the number of valid bits in last word of the message */
556 __HAL_HASH_SET_NBVALIDBITS(Size
);
558 /* Write input buffer in data register */
559 HASH_WriteData(pInBuffer
, Size
);
561 /* Start the digest calculation */
562 __HAL_HASH_START_DIGEST();
565 tickstart
= HAL_GetTick();
567 while(HAL_IS_BIT_SET(HASH
->SR
, HASH_FLAG_BUSY
))
569 /* Check for the Timeout */
570 if(Timeout
!= HAL_MAX_DELAY
)
572 if((Timeout
== 0U)||((HAL_GetTick() - tickstart
) > Timeout
))
575 hhash
->State
= HAL_HASH_STATE_TIMEOUT
;
577 /* Process Unlocked */
585 /* Read the message digest */
586 HASH_GetDigest(pOutBuffer
, 16U);
588 /* Change the HASH state */
589 hhash
->State
= HAL_HASH_STATE_READY
;
591 /* Process Unlocked */
594 /* Return function status */
599 * @brief Initializes the HASH peripheral in MD5 mode then writes the pInBuffer.
600 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
601 * the configuration information for HASH module
602 * @param pInBuffer: Pointer to the input buffer (buffer to be hashed).
603 * @param Size: Length of the input buffer in bytes.
604 * If the Size is multiple of 64 bytes, appending the input buffer is possible.
605 * If the Size is not multiple of 64 bytes, the padding is managed by hardware
606 * and appending the input buffer is no more possible.
609 HAL_StatusTypeDef
HAL_HASH_MD5_Accumulate(HASH_HandleTypeDef
*hhash
, uint8_t *pInBuffer
, uint32_t Size
)
614 /* Change the HASH state */
615 hhash
->State
= HAL_HASH_STATE_BUSY
;
617 /* Check if initialization phase has already been performed */
618 if(hhash
->Phase
== HAL_HASH_PHASE_READY
)
620 /* Select the MD5 mode and reset the HASH processor core, so that the HASH will be ready to compute
621 the message digest of a new message */
622 HASH
->CR
|= HASH_ALGOSELECTION_MD5
| HASH_CR_INIT
;
626 hhash
->Phase
= HAL_HASH_PHASE_PROCESS
;
628 /* Configure the number of valid bits in last word of the message */
629 __HAL_HASH_SET_NBVALIDBITS(Size
);
631 /* Write input buffer in data register */
632 HASH_WriteData(pInBuffer
, Size
);
634 /* Change the HASH state */
635 hhash
->State
= HAL_HASH_STATE_READY
;
637 /* Process Unlocked */
640 /* Return function status */
645 * @brief Initializes the HASH peripheral in SHA1 mode then processes pInBuffer.
646 The digest is available in pOutBuffer.
647 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
648 * the configuration information for HASH module
649 * @param pInBuffer: Pointer to the input buffer (buffer to be hashed).
650 * @param Size: Length of the input buffer in bytes.
651 * If the Size is not multiple of 64 bytes, the padding is managed by hardware.
652 * @param pOutBuffer: Pointer to the computed digest. Its size must be 20 bytes.
653 * @param Timeout: Timeout value
656 HAL_StatusTypeDef
HAL_HASH_SHA1_Start(HASH_HandleTypeDef
*hhash
, uint8_t *pInBuffer
, uint32_t Size
, uint8_t* pOutBuffer
, uint32_t Timeout
)
658 uint32_t tickstart
= 0U;
663 /* Change the HASH state */
664 hhash
->State
= HAL_HASH_STATE_BUSY
;
666 /* Check if initialization phase has already been performed */
667 if(hhash
->Phase
== HAL_HASH_PHASE_READY
)
669 /* Select the SHA1 mode and reset the HASH processor core, so that the HASH will be ready to compute
670 the message digest of a new message */
671 HASH
->CR
|= HASH_ALGOSELECTION_SHA1
| HASH_CR_INIT
;
675 hhash
->Phase
= HAL_HASH_PHASE_PROCESS
;
677 /* Configure the number of valid bits in last word of the message */
678 __HAL_HASH_SET_NBVALIDBITS(Size
);
680 /* Write input buffer in data register */
681 HASH_WriteData(pInBuffer
, Size
);
683 /* Start the digest calculation */
684 __HAL_HASH_START_DIGEST();
687 tickstart
= HAL_GetTick();
689 while(HAL_IS_BIT_SET(HASH
->SR
, HASH_FLAG_BUSY
))
691 /* Check for the Timeout */
692 if(Timeout
!= HAL_MAX_DELAY
)
694 if((Timeout
== 0U)||((HAL_GetTick() - tickstart
) > Timeout
))
697 hhash
->State
= HAL_HASH_STATE_TIMEOUT
;
699 /* Process Unlocked */
707 /* Read the message digest */
708 HASH_GetDigest(pOutBuffer
, 20U);
710 /* Change the HASH state */
711 hhash
->State
= HAL_HASH_STATE_READY
;
713 /* Process Unlocked */
716 /* Return function status */
721 * @brief Initializes the HASH peripheral in SHA1 mode then processes pInBuffer.
722 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
723 * the configuration information for HASH module
724 * @param pInBuffer: Pointer to the input buffer (buffer to be hashed).
725 * @param Size: Length of the input buffer in bytes.
726 * If the Size is not multiple of 64 bytes, the padding is managed by hardware.
727 * @note Input buffer size in bytes must be a multiple of 4 otherwise the digest computation is corrupted.
730 HAL_StatusTypeDef
HAL_HASH_SHA1_Accumulate(HASH_HandleTypeDef
*hhash
, uint8_t *pInBuffer
, uint32_t Size
)
732 /* Check the parameters */
733 assert_param(IS_HASH_SHA1_BUFFER_SIZE(Size
));
738 /* Change the HASH state */
739 hhash
->State
= HAL_HASH_STATE_BUSY
;
741 /* Check if initialization phase has already been performed */
742 if(hhash
->Phase
== HAL_HASH_PHASE_READY
)
744 /* Select the SHA1 mode and reset the HASH processor core, so that the HASH will be ready to compute
745 the message digest of a new message */
746 HASH
->CR
|= HASH_ALGOSELECTION_SHA1
| HASH_CR_INIT
;
750 hhash
->Phase
= HAL_HASH_PHASE_PROCESS
;
752 /* Configure the number of valid bits in last word of the message */
753 __HAL_HASH_SET_NBVALIDBITS(Size
);
755 /* Write input buffer in data register */
756 HASH_WriteData(pInBuffer
, Size
);
758 /* Change the HASH state */
759 hhash
->State
= HAL_HASH_STATE_READY
;
761 /* Process Unlocked */
764 /* Return function status */
772 /** @defgroup HASH_Exported_Functions_Group3 HASH processing functions using interrupt mode
773 * @brief processing functions using interrupt mode.
776 ===============================================================================
777 ##### HASH processing using interrupt mode functions #####
778 ===============================================================================
779 [..] This section provides functions allowing to calculate in interrupt mode
780 the hash value using one of the following algorithms:
789 * @brief Initializes the HASH peripheral in MD5 mode then processes pInBuffer.
790 * The digest is available in pOutBuffer.
791 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
792 * the configuration information for HASH module
793 * @param pInBuffer: Pointer to the input buffer (buffer to be hashed).
794 * @param Size: Length of the input buffer in bytes.
795 * If the Size is not multiple of 64 bytes, the padding is managed by hardware.
796 * @param pOutBuffer: Pointer to the computed digest. Its size must be 16 bytes.
799 HAL_StatusTypeDef
HAL_HASH_MD5_Start_IT(HASH_HandleTypeDef
*hhash
, uint8_t *pInBuffer
, uint32_t Size
, uint8_t* pOutBuffer
)
803 uint32_t buffercounter
;
804 uint32_t inputcounter
;
809 if(hhash
->State
== HAL_HASH_STATE_READY
)
811 /* Change the HASH state */
812 hhash
->State
= HAL_HASH_STATE_BUSY
;
814 hhash
->HashInCount
= Size
;
815 hhash
->pHashInBuffPtr
= pInBuffer
;
816 hhash
->pHashOutBuffPtr
= pOutBuffer
;
818 /* Check if initialization phase has already been performed */
819 if(hhash
->Phase
== HAL_HASH_PHASE_READY
)
821 /* Select the SHA1 mode */
822 HASH
->CR
|= HASH_ALGOSELECTION_MD5
;
823 /* Reset the HASH processor core, so that the HASH will be ready to compute
824 the message digest of a new message */
825 HASH
->CR
|= HASH_CR_INIT
;
827 /* Reset interrupt counter */
828 hhash
->HashITCounter
= 0U;
831 hhash
->Phase
= HAL_HASH_PHASE_PROCESS
;
833 /* Process Unlocked */
836 /* Enable Interrupts */
837 HASH
->IMR
= (HASH_IT_DINI
| HASH_IT_DCI
);
839 /* Return function status */
842 if(__HAL_HASH_GET_FLAG(HASH_FLAG_DCIS
))
844 outputaddr
= (uint32_t)hhash
->pHashOutBuffPtr
;
845 /* Read the Output block from the Output FIFO */
846 *(uint32_t*)(outputaddr
) = __REV(HASH
->HR
[0U]);
848 *(uint32_t*)(outputaddr
) = __REV(HASH
->HR
[1U]);
850 *(uint32_t*)(outputaddr
) = __REV(HASH
->HR
[2U]);
852 *(uint32_t*)(outputaddr
) = __REV(HASH
->HR
[3U]);
854 if(hhash
->HashInCount
== 0U)
856 /* Disable Interrupts */
858 /* Change the HASH state */
859 hhash
->State
= HAL_HASH_STATE_READY
;
860 /* Call digest computation complete callback */
861 HAL_HASH_DgstCpltCallback(hhash
);
863 /* Process Unlocked */
866 /* Return function status */
870 if(__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS
))
872 if(hhash
->HashInCount
>= 68U)
874 inputaddr
= (uint32_t)hhash
->pHashInBuffPtr
;
875 /* Write the Input block in the Data IN register */
876 for(buffercounter
= 0U; buffercounter
< 64U; buffercounter
+=4U)
878 HASH
->DIN
= *(uint32_t*)inputaddr
;
881 if(hhash
->HashITCounter
== 0U)
883 HASH
->DIN
= *(uint32_t*)inputaddr
;
885 if(hhash
->HashInCount
>= 68U)
887 /* Decrement buffer counter */
888 hhash
->HashInCount
-= 68U;
889 hhash
->pHashInBuffPtr
+= 68U;
893 hhash
->HashInCount
= 0U;
894 hhash
->pHashInBuffPtr
+= hhash
->HashInCount
;
896 /* Set Interrupt counter */
897 hhash
->HashITCounter
= 1U;
901 /* Decrement buffer counter */
902 hhash
->HashInCount
-= 64U;
903 hhash
->pHashInBuffPtr
+= 64U;
908 /* Get the buffer address */
909 inputaddr
= (uint32_t)hhash
->pHashInBuffPtr
;
910 /* Get the buffer counter */
911 inputcounter
= hhash
->HashInCount
;
912 /* Disable Interrupts */
913 HASH
->IMR
&= ~(HASH_IT_DINI
);
914 /* Configure the number of valid bits in last word of the message */
915 __HAL_HASH_SET_NBVALIDBITS(inputcounter
);
917 if((inputcounter
> 4U) && (inputcounter
%4U))
919 inputcounter
= (inputcounter
+4U-inputcounter
%4U);
921 else if ((inputcounter
< 4U) && (inputcounter
!= 0U))
925 /* Write the Input block in the Data IN register */
926 for(buffercounter
= 0U; buffercounter
< inputcounter
/4U; buffercounter
++)
928 HASH
->DIN
= *(uint32_t*)inputaddr
;
931 /* Start the digest calculation */
932 __HAL_HASH_START_DIGEST();
933 /* Reset buffer counter */
934 hhash
->HashInCount
= 0U;
935 /* Call Input data transfer complete callback */
936 HAL_HASH_InCpltCallback(hhash
);
940 /* Process Unlocked */
943 /* Return function status */
948 * @brief Initializes the HASH peripheral in SHA1 mode then processes pInBuffer.
949 * The digest is available in pOutBuffer.
950 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
951 * the configuration information for HASH module
952 * @param pInBuffer: Pointer to the input buffer (buffer to be hashed).
953 * @param Size: Length of the input buffer in bytes.
954 * If the Size is not multiple of 64 bytes, the padding is managed by hardware.
955 * @param pOutBuffer: Pointer to the computed digest. Its size must be 20 bytes.
958 HAL_StatusTypeDef
HAL_HASH_SHA1_Start_IT(HASH_HandleTypeDef
*hhash
, uint8_t *pInBuffer
, uint32_t Size
, uint8_t* pOutBuffer
)
962 uint32_t buffercounter
;
963 uint32_t inputcounter
;
968 if(hhash
->State
== HAL_HASH_STATE_READY
)
970 /* Change the HASH state */
971 hhash
->State
= HAL_HASH_STATE_BUSY
;
973 hhash
->HashInCount
= Size
;
974 hhash
->pHashInBuffPtr
= pInBuffer
;
975 hhash
->pHashOutBuffPtr
= pOutBuffer
;
977 /* Check if initialization phase has already been performed */
978 if(hhash
->Phase
== HAL_HASH_PHASE_READY
)
980 /* Select the SHA1 mode */
981 HASH
->CR
|= HASH_ALGOSELECTION_SHA1
;
982 /* Reset the HASH processor core, so that the HASH will be ready to compute
983 the message digest of a new message */
984 HASH
->CR
|= HASH_CR_INIT
;
986 /* Reset interrupt counter */
987 hhash
->HashITCounter
= 0U;
990 hhash
->Phase
= HAL_HASH_PHASE_PROCESS
;
992 /* Process Unlocked */
995 /* Enable Interrupts */
996 HASH
->IMR
= (HASH_IT_DINI
| HASH_IT_DCI
);
998 /* Return function status */
1001 if(__HAL_HASH_GET_FLAG(HASH_FLAG_DCIS
))
1003 outputaddr
= (uint32_t)hhash
->pHashOutBuffPtr
;
1004 /* Read the Output block from the Output FIFO */
1005 *(uint32_t*)(outputaddr
) = __REV(HASH
->HR
[0U]);
1007 *(uint32_t*)(outputaddr
) = __REV(HASH
->HR
[1U]);
1009 *(uint32_t*)(outputaddr
) = __REV(HASH
->HR
[2U]);
1011 *(uint32_t*)(outputaddr
) = __REV(HASH
->HR
[3U]);
1013 *(uint32_t*)(outputaddr
) = __REV(HASH
->HR
[4U]);
1014 if(hhash
->HashInCount
== 0U)
1016 /* Disable Interrupts */
1018 /* Change the HASH state */
1019 hhash
->State
= HAL_HASH_STATE_READY
;
1020 /* Call digest computation complete callback */
1021 HAL_HASH_DgstCpltCallback(hhash
);
1023 /* Process Unlocked */
1024 __HAL_UNLOCK(hhash
);
1026 /* Return function status */
1030 if(__HAL_HASH_GET_FLAG(HASH_FLAG_DINIS
))
1032 if(hhash
->HashInCount
>= 68U)
1034 inputaddr
= (uint32_t)hhash
->pHashInBuffPtr
;
1035 /* Write the Input block in the Data IN register */
1036 for(buffercounter
= 0U; buffercounter
< 64U; buffercounter
+=4U)
1038 HASH
->DIN
= *(uint32_t*)inputaddr
;
1041 if(hhash
->HashITCounter
== 0U)
1043 HASH
->DIN
= *(uint32_t*)inputaddr
;
1044 if(hhash
->HashInCount
>= 68U)
1046 /* Decrement buffer counter */
1047 hhash
->HashInCount
-= 68U;
1048 hhash
->pHashInBuffPtr
+= 68U;
1052 hhash
->HashInCount
= 0U;
1053 hhash
->pHashInBuffPtr
+= hhash
->HashInCount
;
1055 /* Set Interrupt counter */
1056 hhash
->HashITCounter
= 1U;
1060 /* Decrement buffer counter */
1061 hhash
->HashInCount
-= 64U;
1062 hhash
->pHashInBuffPtr
+= 64U;
1067 /* Get the buffer address */
1068 inputaddr
= (uint32_t)hhash
->pHashInBuffPtr
;
1069 /* Get the buffer counter */
1070 inputcounter
= hhash
->HashInCount
;
1071 /* Disable Interrupts */
1072 HASH
->IMR
&= ~(HASH_IT_DINI
);
1073 /* Configure the number of valid bits in last word of the message */
1074 __HAL_HASH_SET_NBVALIDBITS(inputcounter
);
1076 if((inputcounter
> 4U) && (inputcounter
%4U))
1078 inputcounter
= (inputcounter
+4U-inputcounter
%4U);
1080 else if ((inputcounter
< 4U) && (inputcounter
!= 0U))
1084 /* Write the Input block in the Data IN register */
1085 for(buffercounter
= 0U; buffercounter
< inputcounter
/4U; buffercounter
++)
1087 HASH
->DIN
= *(uint32_t*)inputaddr
;
1090 /* Start the digest calculation */
1091 __HAL_HASH_START_DIGEST();
1092 /* Reset buffer counter */
1093 hhash
->HashInCount
= 0U;
1094 /* Call Input data transfer complete callback */
1095 HAL_HASH_InCpltCallback(hhash
);
1099 /* Process Unlocked */
1100 __HAL_UNLOCK(hhash
);
1102 /* Return function status */
1107 * @brief This function handles HASH interrupt request.
1108 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
1109 * the configuration information for HASH module
1112 void HAL_HASH_IRQHandler(HASH_HandleTypeDef
*hhash
)
1114 switch(HASH
->CR
& HASH_CR_ALGO
)
1116 case HASH_ALGOSELECTION_MD5
:
1117 HAL_HASH_MD5_Start_IT(hhash
, NULL
, 0U, NULL
);
1120 case HASH_ALGOSELECTION_SHA1
:
1121 HAL_HASH_SHA1_Start_IT(hhash
, NULL
, 0U, NULL
);
1133 /** @defgroup HASH_Exported_Functions_Group4 HASH processing functions using DMA mode
1134 * @brief processing functions using DMA mode.
1137 ===============================================================================
1138 ##### HASH processing using DMA mode functions #####
1139 ===============================================================================
1140 [..] This section provides functions allowing to calculate in DMA mode
1141 the hash value using one of the following algorithms:
1150 * @brief Initializes the HASH peripheral in MD5 mode then enables DMA to
1151 control data transfer. Use HAL_HASH_MD5_Finish() to get the digest.
1152 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
1153 * the configuration information for HASH module
1154 * @param pInBuffer: Pointer to the input buffer (buffer to be hashed).
1155 * @param Size: Length of the input buffer in bytes.
1156 * If the Size is not multiple of 64 bytes, the padding is managed by hardware.
1157 * @retval HAL status
1159 HAL_StatusTypeDef
HAL_HASH_MD5_Start_DMA(HASH_HandleTypeDef
*hhash
, uint8_t *pInBuffer
, uint32_t Size
)
1161 uint32_t inputaddr
= (uint32_t)pInBuffer
;
1163 /* Process Locked */
1166 /* Change the HASH state */
1167 hhash
->State
= HAL_HASH_STATE_BUSY
;
1169 /* Check if initialization phase has already been performed */
1170 if(hhash
->Phase
== HAL_HASH_PHASE_READY
)
1172 /* Select the MD5 mode and reset the HASH processor core, so that the HASH will be ready to compute
1173 the message digest of a new message */
1174 HASH
->CR
|= HASH_ALGOSELECTION_MD5
| HASH_CR_INIT
;
1177 /* Configure the number of valid bits in last word of the message */
1178 __HAL_HASH_SET_NBVALIDBITS(Size
);
1181 hhash
->Phase
= HAL_HASH_PHASE_PROCESS
;
1183 /* Set the HASH DMA transfer complete callback */
1184 hhash
->hdmain
->XferCpltCallback
= HASH_DMAXferCplt
;
1185 /* Set the DMA error callback */
1186 hhash
->hdmain
->XferErrorCallback
= HASH_DMAError
;
1188 /* Enable the DMA In DMA Stream */
1189 HAL_DMA_Start_IT(hhash
->hdmain
, inputaddr
, (uint32_t)&HASH
->DIN
, (Size
%4U ? (Size
+3U)/4U:Size
/4U));
1191 /* Enable DMA requests */
1192 HASH
->CR
|= (HASH_CR_DMAE
);
1194 /* Process Unlocked */
1195 __HAL_UNLOCK(hhash
);
1197 /* Return function status */
1202 * @brief Returns the computed digest in MD5 mode
1203 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
1204 * the configuration information for HASH module
1205 * @param pOutBuffer: Pointer to the computed digest. Its size must be 16 bytes.
1206 * @param Timeout: Timeout value
1207 * @retval HAL status
1209 HAL_StatusTypeDef
HAL_HASH_MD5_Finish(HASH_HandleTypeDef
*hhash
, uint8_t* pOutBuffer
, uint32_t Timeout
)
1211 uint32_t tickstart
= 0U;
1213 /* Process Locked */
1216 /* Change HASH peripheral state */
1217 hhash
->State
= HAL_HASH_STATE_BUSY
;
1220 tickstart
= HAL_GetTick();
1222 while(HAL_IS_BIT_CLR(HASH
->SR
, HASH_FLAG_DCIS
))
1224 /* Check for the Timeout */
1225 if(Timeout
!= HAL_MAX_DELAY
)
1227 if((Timeout
== 0U)||((HAL_GetTick() - tickstart
) > Timeout
))
1230 hhash
->State
= HAL_HASH_STATE_TIMEOUT
;
1232 /* Process Unlocked */
1233 __HAL_UNLOCK(hhash
);
1240 /* Read the message digest */
1241 HASH_GetDigest(pOutBuffer
, 16U);
1243 /* Change HASH peripheral state */
1244 hhash
->State
= HAL_HASH_STATE_READY
;
1246 /* Process Unlocked */
1247 __HAL_UNLOCK(hhash
);
1249 /* Return function status */
1254 * @brief Initializes the HASH peripheral in SHA1 mode then enables DMA to
1255 control data transfer. Use HAL_HASH_SHA1_Finish() to get the digest.
1256 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
1257 * the configuration information for HASH module
1258 * @param pInBuffer: Pointer to the input buffer (buffer to be hashed).
1259 * @param Size: Length of the input buffer in bytes.
1260 * If the Size is not multiple of 64 bytes, the padding is managed by hardware.
1261 * @retval HAL status
1263 HAL_StatusTypeDef
HAL_HASH_SHA1_Start_DMA(HASH_HandleTypeDef
*hhash
, uint8_t *pInBuffer
, uint32_t Size
)
1265 uint32_t inputaddr
= (uint32_t)pInBuffer
;
1267 /* Process Locked */
1270 /* Change the HASH state */
1271 hhash
->State
= HAL_HASH_STATE_BUSY
;
1273 /* Check if initialization phase has already been performed */
1274 if(hhash
->Phase
== HAL_HASH_PHASE_READY
)
1276 /* Select the SHA1 mode and reset the HASH processor core, so that the HASH will be ready to compute
1277 the message digest of a new message */
1278 HASH
->CR
|= HASH_ALGOSELECTION_SHA1
;
1279 HASH
->CR
|= HASH_CR_INIT
;
1282 /* Configure the number of valid bits in last word of the message */
1283 __HAL_HASH_SET_NBVALIDBITS(Size
);
1286 hhash
->Phase
= HAL_HASH_PHASE_PROCESS
;
1288 /* Set the HASH DMA transfer complete callback */
1289 hhash
->hdmain
->XferCpltCallback
= HASH_DMAXferCplt
;
1290 /* Set the DMA error callback */
1291 hhash
->hdmain
->XferErrorCallback
= HASH_DMAError
;
1293 /* Enable the DMA In DMA Stream */
1294 HAL_DMA_Start_IT(hhash
->hdmain
, inputaddr
, (uint32_t)&HASH
->DIN
, (Size
%4U ? (Size
+3U)/4U:Size
/4U));
1296 /* Enable DMA requests */
1297 HASH
->CR
|= (HASH_CR_DMAE
);
1299 /* Process Unlocked */
1300 __HAL_UNLOCK(hhash
);
1302 /* Return function status */
1307 * @brief Returns the computed digest in SHA1 mode.
1308 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
1309 * the configuration information for HASH module
1310 * @param pOutBuffer: Pointer to the computed digest. Its size must be 20 bytes.
1311 * @param Timeout: Timeout value
1312 * @retval HAL status
1314 HAL_StatusTypeDef
HAL_HASH_SHA1_Finish(HASH_HandleTypeDef
*hhash
, uint8_t* pOutBuffer
, uint32_t Timeout
)
1316 uint32_t tickstart
= 0U;
1318 /* Process Locked */
1321 /* Change HASH peripheral state */
1322 hhash
->State
= HAL_HASH_STATE_BUSY
;
1325 tickstart
= HAL_GetTick();
1326 while(HAL_IS_BIT_CLR(HASH
->SR
, HASH_FLAG_DCIS
))
1328 /* Check for the Timeout */
1329 if(Timeout
!= HAL_MAX_DELAY
)
1331 if((Timeout
== 0U)||((HAL_GetTick() - tickstart
) > Timeout
))
1334 hhash
->State
= HAL_HASH_STATE_TIMEOUT
;
1336 /* Process Unlocked */
1337 __HAL_UNLOCK(hhash
);
1344 /* Read the message digest */
1345 HASH_GetDigest(pOutBuffer
, 20U);
1347 /* Change HASH peripheral state */
1348 hhash
->State
= HAL_HASH_STATE_READY
;
1350 /* Process UnLock */
1351 __HAL_UNLOCK(hhash
);
1353 /* Return function status */
1362 /** @defgroup HASH_Exported_Functions_Group5 HASH-MAC (HMAC) processing functions using polling mode
1363 * @brief HMAC processing functions using polling mode .
1366 ===============================================================================
1367 ##### HMAC processing using polling mode functions #####
1368 ===============================================================================
1369 [..] This section provides functions allowing to calculate in polling mode
1370 the HMAC value using one of the following algorithms:
1379 * @brief Initializes the HASH peripheral in HMAC MD5 mode
1380 * then processes pInBuffer. The digest is available in pOutBuffer
1381 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
1382 * the configuration information for HASH module
1383 * @param pInBuffer: Pointer to the input buffer (buffer to be hashed).
1384 * @param Size: Length of the input buffer in bytes.
1385 * If the Size is not multiple of 64 bytes, the padding is managed by hardware.
1386 * @param pOutBuffer: Pointer to the computed digest. Its size must be 20 bytes.
1387 * @param Timeout: Timeout value
1388 * @retval HAL status
1390 HAL_StatusTypeDef
HAL_HMAC_MD5_Start(HASH_HandleTypeDef
*hhash
, uint8_t *pInBuffer
, uint32_t Size
, uint8_t* pOutBuffer
, uint32_t Timeout
)
1392 uint32_t tickstart
= 0U;
1394 /* Process Locked */
1397 /* Change the HASH state */
1398 hhash
->State
= HAL_HASH_STATE_BUSY
;
1400 /* Check if initialization phase has already been performed */
1401 if(hhash
->Phase
== HAL_HASH_PHASE_READY
)
1403 /* Check if key size is greater than 64 bytes */
1404 if(hhash
->Init
.KeySize
> 64U)
1406 /* Select the HMAC MD5 mode */
1407 HASH
->CR
|= (HASH_ALGOSELECTION_MD5
| HASH_ALGOMODE_HMAC
| HASH_HMAC_KEYTYPE_LONGKEY
| HASH_CR_INIT
);
1411 /* Select the HMAC MD5 mode */
1412 HASH
->CR
|= (HASH_ALGOSELECTION_MD5
| HASH_ALGOMODE_HMAC
| HASH_CR_INIT
);
1417 hhash
->Phase
= HAL_HASH_PHASE_PROCESS
;
1419 /************************** STEP 1 ******************************************/
1420 /* Configure the number of valid bits in last word of the message */
1421 __HAL_HASH_SET_NBVALIDBITS(hhash
->Init
.KeySize
);
1423 /* Write input buffer in data register */
1424 HASH_WriteData(hhash
->Init
.pKey
, hhash
->Init
.KeySize
);
1426 /* Start the digest calculation */
1427 __HAL_HASH_START_DIGEST();
1430 tickstart
= HAL_GetTick();
1432 while(HAL_IS_BIT_SET(HASH
->SR
, HASH_FLAG_BUSY
))
1434 /* Check for the Timeout */
1435 if(Timeout
!= HAL_MAX_DELAY
)
1437 if((Timeout
== 0U)||((HAL_GetTick() - tickstart
) > Timeout
))
1440 hhash
->State
= HAL_HASH_STATE_TIMEOUT
;
1442 /* Process Unlocked */
1443 __HAL_UNLOCK(hhash
);
1449 /************************** STEP 2 ******************************************/
1450 /* Configure the number of valid bits in last word of the message */
1451 __HAL_HASH_SET_NBVALIDBITS(Size
);
1453 /* Write input buffer in data register */
1454 HASH_WriteData(pInBuffer
, Size
);
1456 /* Start the digest calculation */
1457 __HAL_HASH_START_DIGEST();
1460 tickstart
= HAL_GetTick();
1462 while(HAL_IS_BIT_SET(HASH
->SR
, HASH_FLAG_BUSY
))
1464 /* Check for the Timeout */
1465 if(Timeout
!= HAL_MAX_DELAY
)
1467 if((HAL_GetTick() - tickstart
) > Timeout
)
1470 hhash
->State
= HAL_HASH_STATE_TIMEOUT
;
1472 /* Process Unlocked */
1473 __HAL_UNLOCK(hhash
);
1479 /************************** STEP 3 ******************************************/
1480 /* Configure the number of valid bits in last word of the message */
1481 __HAL_HASH_SET_NBVALIDBITS(hhash
->Init
.KeySize
);
1483 /* Write input buffer in data register */
1484 HASH_WriteData(hhash
->Init
.pKey
, hhash
->Init
.KeySize
);
1486 /* Start the digest calculation */
1487 __HAL_HASH_START_DIGEST();
1490 tickstart
= HAL_GetTick();
1492 while(HAL_IS_BIT_SET(HASH
->SR
, HASH_FLAG_BUSY
))
1494 /* Check for the Timeout */
1495 if(Timeout
!= HAL_MAX_DELAY
)
1497 if((HAL_GetTick() - tickstart
) > Timeout
)
1500 hhash
->State
= HAL_HASH_STATE_TIMEOUT
;
1502 /* Process Unlocked */
1503 __HAL_UNLOCK(hhash
);
1510 /* Read the message digest */
1511 HASH_GetDigest(pOutBuffer
, 16U);
1513 /* Change the HASH state */
1514 hhash
->State
= HAL_HASH_STATE_READY
;
1516 /* Process Unlocked */
1517 __HAL_UNLOCK(hhash
);
1519 /* Return function status */
1524 * @brief Initializes the HASH peripheral in HMAC SHA1 mode
1525 * then processes pInBuffer. The digest is available in pOutBuffer.
1526 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
1527 * the configuration information for HASH module
1528 * @param pInBuffer: Pointer to the input buffer (buffer to be hashed).
1529 * @param Size: Length of the input buffer in bytes.
1530 * If the Size is not multiple of 64 bytes, the padding is managed by hardware.
1531 * @param pOutBuffer: Pointer to the computed digest. Its size must be 20 bytes.
1532 * @param Timeout: Timeout value
1533 * @retval HAL status
1535 HAL_StatusTypeDef
HAL_HMAC_SHA1_Start(HASH_HandleTypeDef
*hhash
, uint8_t *pInBuffer
, uint32_t Size
, uint8_t* pOutBuffer
, uint32_t Timeout
)
1537 uint32_t tickstart
= 0U;
1539 /* Process Locked */
1542 /* Change the HASH state */
1543 hhash
->State
= HAL_HASH_STATE_BUSY
;
1545 /* Check if initialization phase has already been performed */
1546 if(hhash
->Phase
== HAL_HASH_PHASE_READY
)
1548 /* Check if key size is greater than 64 bytes */
1549 if(hhash
->Init
.KeySize
> 64U)
1551 /* Select the HMAC SHA1 mode */
1552 HASH
->CR
|= (HASH_ALGOSELECTION_SHA1
| HASH_ALGOMODE_HMAC
| HASH_HMAC_KEYTYPE_LONGKEY
| HASH_CR_INIT
);
1556 /* Select the HMAC SHA1 mode */
1557 HASH
->CR
|= (HASH_ALGOSELECTION_SHA1
| HASH_ALGOMODE_HMAC
| HASH_CR_INIT
);
1562 hhash
->Phase
= HAL_HASH_PHASE_PROCESS
;
1564 /************************** STEP 1 ******************************************/
1565 /* Configure the number of valid bits in last word of the message */
1566 __HAL_HASH_SET_NBVALIDBITS(hhash
->Init
.KeySize
);
1568 /* Write input buffer in data register */
1569 HASH_WriteData(hhash
->Init
.pKey
, hhash
->Init
.KeySize
);
1571 /* Start the digest calculation */
1572 __HAL_HASH_START_DIGEST();
1575 tickstart
= HAL_GetTick();
1577 while(HAL_IS_BIT_SET(HASH
->SR
, HASH_FLAG_BUSY
))
1579 /* Check for the Timeout */
1580 if(Timeout
!= HAL_MAX_DELAY
)
1582 if((Timeout
== 0U)||((HAL_GetTick() - tickstart
) > Timeout
))
1585 hhash
->State
= HAL_HASH_STATE_TIMEOUT
;
1587 /* Process Unlocked */
1588 __HAL_UNLOCK(hhash
);
1594 /************************** STEP 2 ******************************************/
1595 /* Configure the number of valid bits in last word of the message */
1596 __HAL_HASH_SET_NBVALIDBITS(Size
);
1598 /* Write input buffer in data register */
1599 HASH_WriteData(pInBuffer
, Size
);
1601 /* Start the digest calculation */
1602 __HAL_HASH_START_DIGEST();
1605 tickstart
= HAL_GetTick();
1607 while(HAL_IS_BIT_SET(HASH
->SR
, HASH_FLAG_BUSY
))
1609 /* Check for the Timeout */
1610 if(Timeout
!= HAL_MAX_DELAY
)
1612 if((HAL_GetTick() - tickstart
) > Timeout
)
1615 hhash
->State
= HAL_HASH_STATE_TIMEOUT
;
1617 /* Process Unlocked */
1618 __HAL_UNLOCK(hhash
);
1624 /************************** STEP 3 ******************************************/
1625 /* Configure the number of valid bits in last word of the message */
1626 __HAL_HASH_SET_NBVALIDBITS(hhash
->Init
.KeySize
);
1628 /* Write input buffer in data register */
1629 HASH_WriteData(hhash
->Init
.pKey
, hhash
->Init
.KeySize
);
1631 /* Start the digest calculation */
1632 __HAL_HASH_START_DIGEST();
1635 tickstart
= HAL_GetTick();
1637 while(HAL_IS_BIT_SET(HASH
->SR
, HASH_FLAG_BUSY
))
1639 /* Check for the Timeout */
1640 if(Timeout
!= HAL_MAX_DELAY
)
1642 if((HAL_GetTick() - tickstart
) > Timeout
)
1645 hhash
->State
= HAL_HASH_STATE_TIMEOUT
;
1647 /* Process Unlocked */
1648 __HAL_UNLOCK(hhash
);
1654 /* Read the message digest */
1655 HASH_GetDigest(pOutBuffer
, 20U);
1657 /* Change the HASH state */
1658 hhash
->State
= HAL_HASH_STATE_READY
;
1660 /* Process Unlocked */
1661 __HAL_UNLOCK(hhash
);
1663 /* Return function status */
1671 /** @defgroup HASH_Exported_Functions_Group6 HASH-MAC (HMAC) processing functions using DMA mode
1672 * @brief HMAC processing functions using DMA mode .
1675 ===============================================================================
1676 ##### HMAC processing using DMA mode functions #####
1677 ===============================================================================
1678 [..] This section provides functions allowing to calculate in DMA mode
1679 the HMAC value using one of the following algorithms:
1688 * @brief Initializes the HASH peripheral in HMAC MD5 mode
1689 * then enables DMA to control data transfer.
1690 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
1691 * the configuration information for HASH module
1692 * @param pInBuffer: Pointer to the input buffer (buffer to be hashed).
1693 * @param Size: Length of the input buffer in bytes.
1694 * If the Size is not multiple of 64 bytes, the padding is managed by hardware.
1695 * @retval HAL status
1697 HAL_StatusTypeDef
HAL_HMAC_MD5_Start_DMA(HASH_HandleTypeDef
*hhash
, uint8_t *pInBuffer
, uint32_t Size
)
1699 uint32_t inputaddr
= 0U;
1701 /* Process Locked */
1704 /* Change the HASH state */
1705 hhash
->State
= HAL_HASH_STATE_BUSY
;
1707 /* Save buffer pointer and size in handle */
1708 hhash
->pHashInBuffPtr
= pInBuffer
;
1709 hhash
->HashBuffSize
= Size
;
1710 hhash
->HashInCount
= 0U;
1712 /* Check if initialization phase has already been performed */
1713 if(hhash
->Phase
== HAL_HASH_PHASE_READY
)
1715 /* Check if key size is greater than 64 bytes */
1716 if(hhash
->Init
.KeySize
> 64U)
1718 /* Select the HMAC MD5 mode */
1719 HASH
->CR
|= (HASH_ALGOSELECTION_MD5
| HASH_ALGOMODE_HMAC
| HASH_HMAC_KEYTYPE_LONGKEY
| HASH_CR_INIT
);
1723 /* Select the HMAC MD5 mode */
1724 HASH
->CR
|= (HASH_ALGOSELECTION_MD5
| HASH_ALGOMODE_HMAC
| HASH_CR_INIT
);
1729 hhash
->Phase
= HAL_HASH_PHASE_PROCESS
;
1731 /* Configure the number of valid bits in last word of the message */
1732 __HAL_HASH_SET_NBVALIDBITS(hhash
->Init
.KeySize
);
1734 /* Get the key address */
1735 inputaddr
= (uint32_t)(hhash
->Init
.pKey
);
1737 /* Set the HASH DMA transfer complete callback */
1738 hhash
->hdmain
->XferCpltCallback
= HASH_DMAXferCplt
;
1739 /* Set the DMA error callback */
1740 hhash
->hdmain
->XferErrorCallback
= HASH_DMAError
;
1742 /* Enable the DMA In DMA Stream */
1743 HAL_DMA_Start_IT(hhash
->hdmain
, inputaddr
, (uint32_t)&HASH
->DIN
, (hhash
->Init
.KeySize
%4U ? (hhash
->Init
.KeySize
+3U)/4U:hhash
->Init
.KeySize
/4U));
1744 /* Enable DMA requests */
1745 HASH
->CR
|= (HASH_CR_DMAE
);
1747 /* Process Unlocked */
1748 __HAL_UNLOCK(hhash
);
1750 /* Return function status */
1755 * @brief Initializes the HASH peripheral in HMAC SHA1 mode
1756 * then enables DMA to control data transfer.
1757 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
1758 * the configuration information for HASH module
1759 * @param pInBuffer: Pointer to the input buffer (buffer to be hashed).
1760 * @param Size: Length of the input buffer in bytes.
1761 * If the Size is not multiple of 64 bytes, the padding is managed by hardware.
1762 * @retval HAL status
1764 HAL_StatusTypeDef
HAL_HMAC_SHA1_Start_DMA(HASH_HandleTypeDef
*hhash
, uint8_t *pInBuffer
, uint32_t Size
)
1766 uint32_t inputaddr
= 0U;
1768 /* Process Locked */
1771 /* Change the HASH state */
1772 hhash
->State
= HAL_HASH_STATE_BUSY
;
1774 /* Save buffer pointer and size in handle */
1775 hhash
->pHashInBuffPtr
= pInBuffer
;
1776 hhash
->HashBuffSize
= Size
;
1777 hhash
->HashInCount
= 0U;
1779 /* Check if initialization phase has already been performed */
1780 if(hhash
->Phase
== HAL_HASH_PHASE_READY
)
1782 /* Check if key size is greater than 64 bytes */
1783 if(hhash
->Init
.KeySize
> 64U)
1785 /* Select the HMAC SHA1 mode */
1786 HASH
->CR
|= (HASH_ALGOSELECTION_SHA1
| HASH_ALGOMODE_HMAC
| HASH_HMAC_KEYTYPE_LONGKEY
| HASH_CR_INIT
);
1790 /* Select the HMAC SHA1 mode */
1791 HASH
->CR
|= (HASH_ALGOSELECTION_SHA1
| HASH_ALGOMODE_HMAC
| HASH_CR_INIT
);
1796 hhash
->Phase
= HAL_HASH_PHASE_PROCESS
;
1798 /* Configure the number of valid bits in last word of the message */
1799 __HAL_HASH_SET_NBVALIDBITS(hhash
->Init
.KeySize
);
1801 /* Get the key address */
1802 inputaddr
= (uint32_t)(hhash
->Init
.pKey
);
1804 /* Set the HASH DMA transfer complete callback */
1805 hhash
->hdmain
->XferCpltCallback
= HASH_DMAXferCplt
;
1806 /* Set the DMA error callback */
1807 hhash
->hdmain
->XferErrorCallback
= HASH_DMAError
;
1809 /* Enable the DMA In DMA Stream */
1810 HAL_DMA_Start_IT(hhash
->hdmain
, inputaddr
, (uint32_t)&HASH
->DIN
, (hhash
->Init
.KeySize
%4U ? (hhash
->Init
.KeySize
+3U)/4U:hhash
->Init
.KeySize
/4U));
1811 /* Enable DMA requests */
1812 HASH
->CR
|= (HASH_CR_DMAE
);
1814 /* Process Unlocked */
1815 __HAL_UNLOCK(hhash
);
1817 /* Return function status */
1825 /** @defgroup HASH_Exported_Functions_Group7 Peripheral State functions
1826 * @brief Peripheral State functions.
1829 ===============================================================================
1830 ##### Peripheral State functions #####
1831 ===============================================================================
1833 This subsection permits to get in run-time the status of the peripheral.
1840 * @brief return the HASH state
1841 * @param hhash: pointer to a HASH_HandleTypeDef structure that contains
1842 * the configuration information for HASH module
1845 HAL_HASH_StateTypeDef
HAL_HASH_GetState(HASH_HandleTypeDef
*hhash
)
1847 return hhash
->State
;
1858 #endif /* STM32F415xx || STM32F417xx || STM32F437xx || STM32F439xx || STM32F479xx */
1859 #endif /* HAL_HASH_MODULE_ENABLED */
1868 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/