From d068ae48d622f18f0e76f86985225b9aa151be4b Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Fri, 28 May 2021 15:30:26 +0300 Subject: [PATCH] Add header file for arhitecture/implementation specific px4 crypto and configuration for cmake Signed-off-by: Jukka Laitinen --- cmake/px4_add_board.cmake | 14 +++ .../px4_platform_common/crypto_algorithms.h | 46 +++++++ .../px4_platform_common/crypto_backend.h | 115 ++++++++++++++++++ 3 files changed, 175 insertions(+) create mode 100644 platforms/common/include/px4_platform_common/crypto_algorithms.h create mode 100644 platforms/common/include/px4_platform_common/crypto_backend.h diff --git a/cmake/px4_add_board.cmake b/cmake/px4_add_board.cmake index 32e04b80dd..ba41d44cf6 100644 --- a/cmake/px4_add_board.cmake +++ b/cmake/px4_add_board.cmake @@ -61,6 +61,8 @@ # [ TESTING ] # [ LINKER_PREFIX ] # [ ETHERNET ] +# [ CRYPTO ] +# [ KEYSTORE ] # ) # # Input: @@ -86,6 +88,8 @@ # TESTING : flag to enable automatic inclusion of PX4 testing modules # LINKER_PREFIX : optional to prefix on the Linker script. # ETHERNET : flag to indicate that ethernet is enabled +# CRYPTO : Crypto implementation selection +# KEYSTORE : Keystore implememntation selection # # # Example: @@ -149,6 +153,8 @@ function(px4_add_board) UAVCAN_INTERFACES UAVCAN_TIMER_OVERRIDE LINKER_PREFIX + CRYPTO + KEYSTORE MULTI_VALUE DRIVERS MODULES @@ -267,6 +273,14 @@ function(px4_add_board) set(PX4_ETHERNET "1" CACHE INTERNAL "ethernet enabled" FORCE) endif() + if(CRYPTO) + set(PX4_CRYPTO ${CRYPTO} CACHE STRING "PX4 crypto implementation" FORCE) + endif() + + if(KEYSTORE) + set(PX4_KEYSTORE ${KEYSTORE} CACHE STRING "PX4 keystore implementation" FORCE) + endif() + if(LINKER_PREFIX) set(PX4_BOARD_LINKER_PREFIX ${LINKER_PREFIX} CACHE STRING "PX4 board linker prefix" FORCE) else() diff --git a/platforms/common/include/px4_platform_common/crypto_algorithms.h b/platforms/common/include/px4_platform_common/crypto_algorithms.h new file mode 100644 index 0000000000..32a4a44f5f --- /dev/null +++ b/platforms/common/include/px4_platform_common/crypto_algorithms.h @@ -0,0 +1,46 @@ +/**************************************************************************** + * + * Copyright (c) 2021 Technology Innovation Institute. All rights reserved. + * + * 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 PX4 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. + * + ****************************************************************************/ + +#pragma once + +#include + +/* List of all the supported crypto algorithms in PX4 */ + +typedef enum { + CRYPTO_NONE = 0, + CRYPTO_ED25519 = 1, + CRYPTO_XCHACHA20 = 2, + CRYPTO_AES = 3, + CRYPTO_RSA_OAEP = 4, +} px4_crypto_algorithm_t; diff --git a/platforms/common/include/px4_platform_common/crypto_backend.h b/platforms/common/include/px4_platform_common/crypto_backend.h new file mode 100644 index 0000000000..0befa6cf08 --- /dev/null +++ b/platforms/common/include/px4_platform_common/crypto_backend.h @@ -0,0 +1,115 @@ +/**************************************************************************** + * + * Copyright (c) 2021 Technology Innovation Institute. All rights reserved. + * + * 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 PX4 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. + * + ****************************************************************************/ + +#pragma once + +#if defined(__cplusplus) +extern "C" { +#endif + +#include +#include +#include +#include "crypto_backend_definitions.h" + +/* + * Keystore access functions + */ + +void keystore_init(void); + +/* + * Open a session for accessing security keys + */ + +keystore_session_handle_t keystore_open(void); + +/* + * Close the keystore session + * handle: handle to the session to be closed + */ + +void keystore_close(keystore_session_handle_t *handle); + +/* + * Get a key from keystore + * handle: a handle to an open keystore + * idx: key index in keystore + * key_buf: output buffer for the key + * key_buf_size: size of the provided output buffer + * returns the size of the key in keystore + */ +size_t keystore_get_key(keystore_session_handle_t handle, uint8_t idx, uint8_t *key_buf, size_t key_buf_size); + +/* + * Architecture specific PX4 Crypto API functions + */ + +/* + * Initialize hw level crypto + * This has to be called before any other crypto operations + */ + +void crypto_init(void); + +/* + * Open a session for performing crypto functions + * algorithm: The crypto algorithm to be used in this session + */ + +crypto_session_handle_t crypto_open(px4_crypto_algorithm_t algorithm); + +/* + * Close the session for performing crypto operations + * handle: handle to the session to be closed + */ + +void crypto_close(crypto_session_handle_t *handle); + +/* + * Perform signature check using an open session to crypto + * handle: session handle, returned by open + * key_index: index to the key used for signature check + * message: pointer to the data to be checked + * message_size: size of the data + */ + +bool crypto_signature_check(crypto_session_handle_t handle, + uint8_t key_index, + const uint8_t *signature, + const uint8_t *message, + size_t message_size); + +#if defined(__cplusplus) +} // extern "C" +#endif