summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-02-04 06:49:05 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-02-04 06:49:05 -0600
commitca83154fa5a06295072fdbbcfb616b32314b86a3 (patch)
tree6689888274b3148d9becbe1052aafc7837720b10 /nuttx
parent0b2fa1345880e3d26c810e22fba7022eddb8b3f5 (diff)
downloadpx4-nuttx-ca83154fa5a06295072fdbbcfb616b32314b86a3.tar.gz
px4-nuttx-ca83154fa5a06295072fdbbcfb616b32314b86a3.tar.bz2
px4-nuttx-ca83154fa5a06295072fdbbcfb616b32314b86a3.zip
STM32: Add driver for STM32L162XX AES peripheral. Signed-off-by: Juha Niskanen <juha.niskanen@haltian.com>
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/stm32/Make.defs6
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32l15xxx_aes.h117
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_aes.c319
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_aes.h71
-rw-r--r--nuttx/crypto/crypto.c2
-rw-r--r--nuttx/crypto/testmngr.c10
-rw-r--r--nuttx/include/nuttx/crypto/crypto.h4
7 files changed, 527 insertions, 2 deletions
diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
index 4369d9d74..9f1a5b28c 100644
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -1,7 +1,7 @@
############################################################################
# arch/arm/src/stm32/Make.defs
#
-# Copyright (C) 2009, 2011-2014 Gregory Nutt. All rights reserved.
+# Copyright (C) 2009, 2011-2015 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
@@ -226,3 +226,7 @@ endif
ifeq ($(CONFIG_DEBUG),y)
CHIP_CSRCS += stm32_dumpgpio.c
endif
+
+ifeq ($(CONFIG_CRYPTO_AES),y)
+CHIP_CSRCS += stm32_aes.c
+endif
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32l15xxx_aes.h b/nuttx/arch/arm/src/stm32/chip/stm32l15xxx_aes.h
new file mode 100644
index 000000000..a692a3144
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/chip/stm32l15xxx_aes.h
@@ -0,0 +1,117 @@
+/********************************************************************************************
+ * arch/arm/src/stm32/chip/stm32l15xxx_aes.h
+ * AES hardware accelerator for STM32L162xx advanced ARM-based
+ * 32-bit MCUs
+ *
+ * Copyright (C) 2015 Haltian Ltd. All rights reserved.
+ * Author: Juha Niskanen <juha.niskanen@haltian.com>
+ *
+ * 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 NuttX 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 OWNER 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.
+ *
+ ********************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_STM32_CHIP_STM32L15XXX_AES_H
+#define __ARCH_ARM_SRC_STM32_CHIP_STM32L15XXX_AES_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/stm32l15xxx_memorymap.h"
+
+/********************************************************************************************
+ * Pre-processor Definitions
+ ********************************************************************************************/
+
+/* AES register offsets *********************************************************************/
+
+#define STM32_AES_CR_OFFSET 0x0000 /* Control Register */
+#define STM32_AES_SR_OFFSET 0x0004 /* Status Register */
+#define STM32_AES_DINR_OFFSET 0x0008 /* Data Input Register */
+#define STM32_AES_DOUTR_OFFSET 0x000C /* Data Output Register */
+#define STM32_AES_KEYR0_OFFSET 0x0010 /* AES Key Register 0 */
+#define STM32_AES_KEYR1_OFFSET 0x0014 /* AES Key Register 1 */
+#define STM32_AES_KEYR2_OFFSET 0x0018 /* AES Key Register 2 */
+#define STM32_AES_KEYR3_OFFSET 0x001C /* AES Key Register 3 */
+#define STM32_AES_IVR0_OFFSET 0x0020 /* AES Initialization Vector Register 0 */
+#define STM32_AES_IVR1_OFFSET 0x0024 /* AES Initialization Vector Register 1 */
+#define STM32_AES_IVR2_OFFSET 0x0028 /* AES Initialization Vector Register 2 */
+#define STM32_AES_IVR3_OFFSET 0x002C /* AES Initialization Vector Register 3 */
+
+/* AES register addresses *******************************************************************/
+
+#define STM32_AES_CR (STM32_AES_BASE + STM32_AES_CR_OFFSET)
+#define STM32_AES_SR (STM32_AES_BASE + STM32_AES_SR_OFFSET)
+#define STM32_AES_DINR (STM32_AES_BASE + STM32_AES_DINR_OFFSET)
+#define STM32_AES_DOUTR (STM32_AES_BASE + STM32_AES_DOUTR_OFFSET)
+#define STM32_AES_KEYR0 (STM32_AES_BASE + STM32_AES_KEYR0_OFFSET)
+#define STM32_AES_KEYR1 (STM32_AES_BASE + STM32_AES_KEYR1_OFFSET)
+#define STM32_AES_KEYR2 (STM32_AES_BASE + STM32_AES_KEYR2_OFFSET)
+#define STM32_AES_KEYR3 (STM32_AES_BASE + STM32_AES_KEYR3_OFFSET)
+#define STM32_AES_IVR0 (STM32_AES_BASE + STM32_AES_IVR0_OFFSET)
+#define STM32_AES_IVR1 (STM32_AES_BASE + STM32_AES_IVR1_OFFSET)
+#define STM32_AES_IVR2 (STM32_AES_BASE + STM32_AES_IVR2_OFFSET)
+#define STM32_AES_IVR3 (STM32_AES_BASE + STM32_AES_IVR3_OFFSET)
+
+/* AES register bit definitions *************************************************************/
+
+/* AES_CR register */
+
+#define AES_CR_EN (1 << 0) /* AES Enable */
+#define AES_CR_DATATYPE (1 << 1) /* Data type selection */
+# define AES_CR_DATATYPE_LE (0x0 << 1)
+# define AES_CR_DATATYPE_BE (0x2 << 1)
+
+#define AES_CR_MODE (1 << 3) /* AES Mode of operation */
+# define AES_CR_MODE_ENCRYPT (0x0 << 3)
+# define AES_CR_MODE_KEYDERIV (0x1 << 3)
+# define AES_CR_MODE_DECRYPT (0x2 << 3)
+# define AES_CR_MODE_DECRYPT_KEYDERIV (0x3 << 3)
+
+#define AES_CR_CHMOD (1 << 5) /* AES Chaining Mode */
+# define AES_CR_CHMOD_ECB (0x0 << 5)
+# define AES_CR_CHMOD_CBC (0x1 << 5)
+# define AES_CR_CHMOD_CTR (0x2 << 5)
+
+#define AES_CR_CCFC (1 << 7) /* Computation Complete Flag Clear */
+#define AES_CR_ERRC (1 << 8) /* Error Clear */
+#define AES_CR_CCIE (1 << 9) /* Computation Complete Interrupt Enable */
+#define AES_CR_ERRIE (1 << 10) /* Error Interrupt Enable */
+#define AES_CR_DMAINEN (1 << 11) /* DMA Enable Input */
+#define AES_CR_DMAOUTEN (1 << 12) /* DMA Enable Output */
+
+/* AES_SR register */
+
+#define AES_SR_CCF (1 << 0) /* Computation Complete Flag */
+#define AES_SR_RDERR (1 << 1) /* Read Error Flag */
+#define AES_SR_WRERR (1 << 2) /* Write Error Flag */
+
+#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32L15XXX_AES_H */
diff --git a/nuttx/arch/arm/src/stm32/stm32_aes.c b/nuttx/arch/arm/src/stm32/stm32_aes.c
new file mode 100644
index 000000000..e2882264b
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_aes.c
@@ -0,0 +1,319 @@
+/****************************************************************************
+ * arch/arm/src/stm32/stm32_aes.c
+ *
+ * Copyright (C) 2015 Haltian Ltd. All rights reserved.
+ * Author: Juha Niskanen <juha.niskanen@haltian.com>
+ *
+ * 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 NuttX 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 OWNER 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdlib.h>
+#include <semaphore.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/crypto/crypto.h>
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "chip.h"
+#include "stm32_rcc.h"
+#include "stm32_aes.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define AES_BLOCK_SIZE 16
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static void aes_enable(bool on);
+static void aes_ccfc(void);
+static void aes_setkey(const void *key, size_t key_len);
+static void aes_setiv(const void *iv);
+static void aes_encryptblock(void *block_out, const void *block_in);
+static int aes_setup_cr(int mode, int encrypt);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static sem_t aes_lock;
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+static void aes_enable(bool on)
+{
+ uint32_t regval;
+
+ regval = getreg32(STM32_AES_CR);
+ if (on)
+ regval |= AES_CR_EN;
+ else
+ regval &= ~AES_CR_EN;
+ putreg32(regval, STM32_AES_CR);
+}
+
+/* Clear AES_SR_CCF status register bit */
+
+static void aes_ccfc(void)
+{
+ uint32_t regval;
+
+ regval = getreg32(STM32_AES_CR);
+ regval |= AES_CR_CCFC;
+ putreg32(regval, STM32_AES_CR);
+}
+
+static void aes_setkey(const void *key, size_t key_len)
+{
+ uint32_t *in = (uint32_t *)key;
+
+ (void)key_len;
+
+ putreg32(__builtin_bswap32(*in), STM32_AES_KEYR3);
+ in++;
+ putreg32(__builtin_bswap32(*in), STM32_AES_KEYR2);
+ in++;
+ putreg32(__builtin_bswap32(*in), STM32_AES_KEYR1);
+ in++;
+ putreg32(__builtin_bswap32(*in), STM32_AES_KEYR0);
+}
+
+static void aes_setiv(const void *iv)
+{
+ uint32_t *in = (uint32_t *)iv;
+
+ putreg32(__builtin_bswap32(*in), STM32_AES_IVR3);
+ in++;
+ putreg32(__builtin_bswap32(*in), STM32_AES_IVR2);
+ in++;
+ putreg32(__builtin_bswap32(*in), STM32_AES_IVR1);
+ in++;
+ putreg32(__builtin_bswap32(*in), STM32_AES_IVR0);
+}
+
+static void aes_encryptblock(void *block_out, const void *block_in)
+{
+ uint32_t *in = (uint32_t *)block_in;
+ uint32_t *out = (uint32_t *)block_out;
+
+ putreg32(*in, STM32_AES_DINR);
+ in++;
+ putreg32(*in, STM32_AES_DINR);
+ in++;
+ putreg32(*in, STM32_AES_DINR);
+ in++;
+ putreg32(*in, STM32_AES_DINR);
+
+ while(!(getreg32(STM32_AES_SR) & AES_SR_CCF))
+ ;
+ aes_ccfc();
+
+ *out = getreg32(STM32_AES_DOUTR);
+ out++;
+ *out = getreg32(STM32_AES_DOUTR);
+ out++;
+ *out = getreg32(STM32_AES_DOUTR);
+ out++;
+ *out = getreg32(STM32_AES_DOUTR);
+}
+
+static int aes_setup_cr(int mode, int encrypt)
+{
+ uint32_t regval = 0;
+
+ regval |= AES_CR_DATATYPE_BE;
+
+ switch (mode)
+ {
+ case AES_MODE_ECB:
+ regval |= AES_CR_CHMOD_ECB;
+ break;
+
+ case AES_MODE_CBC:
+ regval |= AES_CR_CHMOD_CBC;
+ break;
+
+ case AES_MODE_CTR:
+ regval |= AES_CR_CHMOD_CTR;
+ break;
+
+ default:
+ return -EINVAL;
+ }
+
+ if (encrypt)
+ {
+ regval |= AES_CR_MODE_ENCRYPT;
+ }
+ else
+ {
+ if (mode == AES_MODE_CTR)
+ {
+ regval |= AES_CR_MODE_DECRYPT;
+ }
+ else
+ {
+ regval |= AES_CR_MODE_DECRYPT_KEYDERIV;
+ }
+ }
+
+ putreg32(regval, STM32_AES_CR);
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+int aes_cypher(void *out, const void *in, uint32_t size, const void *iv,
+ const void *key, uint32_t keysize, int mode, int encrypt)
+{
+ int ret = OK;
+
+ if ((size & (AES_BLOCK_SIZE-1)) != 0)
+ {
+ return -EINVAL;
+ }
+
+ if (keysize != 16)
+ {
+ return -EINVAL;
+ }
+
+ ret = sem_wait(&aes_lock);
+ if (ret < 0)
+ {
+ return ret;
+ }
+
+ /* AES must be disabled before changing mode, key or IV. */
+
+ aes_enable(false);
+ ret = aes_setup_cr(mode, encrypt);
+ if (ret < 0)
+ {
+ goto out;
+ }
+
+ aes_setkey(key, keysize);
+ if (iv)
+ {
+ aes_setiv(iv);
+ }
+
+ aes_enable(true);
+ while (size)
+ {
+ aes_encryptblock(out, in);
+ out = (uint8_t *)out + AES_BLOCK_SIZE;
+ in = (uint8_t *)in + AES_BLOCK_SIZE;
+ size -= AES_BLOCK_SIZE;
+ }
+
+ aes_enable(false);
+
+out:
+ sem_post(&aes_lock);
+ return ret;
+}
+
+int up_aesreset(void)
+{
+ irqstate_t flags;
+ uint32_t regval;
+
+ flags = irqsave();
+
+ regval = getreg32(STM32_RCC_AHBRSTR);
+ regval |= RCC_AHBRSTR_AESRST;
+ putreg32(regval, STM32_RCC_AHBRSTR);
+ regval &= ~RCC_AHBRSTR_AESRST;
+ putreg32(regval, STM32_RCC_AHBRSTR);
+
+ irqrestore(flags);
+
+ return OK;
+}
+
+int up_aesinitialize(void)
+{
+ uint32_t regval;
+
+ sem_init(&aes_lock, 0, 1);
+
+ regval = getreg32(STM32_RCC_AHBENR);
+ regval |= RCC_AHBENR_AESEN;
+ putreg32(regval, STM32_RCC_AHBENR);
+
+ aes_enable(false);
+
+ return OK;
+}
+
+int up_aesuninitialize(void)
+{
+ uint32_t regval;
+
+ aes_enable(false);
+
+ regval = getreg32(STM32_RCC_AHBENR);
+ regval &= ~RCC_AHBENR_AESEN;
+ putreg32(regval, STM32_RCC_AHBENR);
+
+ sem_destroy(&aes_lock);
+
+ return OK;
+}
diff --git a/nuttx/arch/arm/src/stm32/stm32_aes.h b/nuttx/arch/arm/src/stm32/stm32_aes.h
new file mode 100644
index 000000000..50c0d22ea
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_aes.h
@@ -0,0 +1,71 @@
+/************************************************************************************
+ * arch/arm/src/stm32/stm32_aes.h
+ *
+ * Copyright (C) 2014 Haltian Ltd. All rights reserved.
+ * Author: Juha Niskanen <juha.niskanen@haltian.com>
+ *
+ * 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 NuttX 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 OWNER 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_STM32_STM32_AES_H
+#define __ARCH_ARM_SRC_STM32_STM32_AES_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+
+#include "chip.h"
+
+/* Only the STM32L162 devices have AES, but we don't bother with exact macros for
+ * simplicity.
+ */
+
+#ifdef CONFIG_STM32_STM32L15XX
+# include "chip/stm32l15xxx_aes.h"
+#else
+# error "Unknown chip for AES"
+#endif
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_STM32_STM32_AES_H */
diff --git a/nuttx/crypto/crypto.c b/nuttx/crypto/crypto.c
index b0c664097..9b4391b5b 100644
--- a/nuttx/crypto/crypto.c
+++ b/nuttx/crypto/crypto.c
@@ -64,7 +64,7 @@
* Public Functions
****************************************************************************/
-void up_cryptoinitialize(void)
+int up_cryptoinitialize(void)
{
#if defined(CONFIG_CRYPTO_AES) || defined(CONFIG_CRYPTO_ALGTEST)
int res;
diff --git a/nuttx/crypto/testmngr.c b/nuttx/crypto/testmngr.c
index f9f6a8b4f..d7a932982 100644
--- a/nuttx/crypto/testmngr.c
+++ b/nuttx/crypto/testmngr.c
@@ -63,6 +63,16 @@
static int do_test_aes(FAR struct cipher_testvec* test, int mode, int encrypt)
{
FAR void *out = kmm_zalloc(test->rlen);
+
+#ifdef CONFIG_STM32_STM32L15XX
+ /* This architecture only has 128-bit AES in chip. */
+
+ if (test->klen != 16)
+ {
+ return OK;
+ }
+#endif
+
int res = aes_cypher(out, test->input, test->ilen, test->iv, test->key,
test->klen, mode, encrypt);
if (res == OK)
diff --git a/nuttx/include/nuttx/crypto/crypto.h b/nuttx/include/nuttx/crypto/crypto.h
index 090fe77c2..9cca6cdc8 100644
--- a/nuttx/include/nuttx/crypto/crypto.h
+++ b/nuttx/include/nuttx/crypto/crypto.h
@@ -85,6 +85,10 @@ int aes_cypher(FAR void *out, FAR const void *in, uint32_t size, FAR const void
FAR const void *key, uint32_t keysize, int mode, int encrypt);
#endif
+#if defined(CONFIG_CRYPTO_ALGTEST)
+int crypto_test(void);
+#endif
+
#undef EXTERN
#if defined(__cplusplus)
}