From db3baf6c26d610828abad37b1835da9521a7d376 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Fri, 9 Oct 2020 14:14:21 +0300 Subject: [PATCH] Add an ioctl interface for userspace to kernel calls This adds an ioctl interface for NuttX protected build, allowing system calls from user space to kernel for uORB, HRT and crypto Signed-off-by: Jukka Laitinen --- platforms/nuttx/src/px4/common/board_ctrl.c | 104 ++++++++++++++++++ .../common/include/px4_platform/board_ctrl.h | 63 +++++++++++ platforms/nuttx/src/px4/common/px4_init.cpp | 10 ++ .../src/px4/common/px4_protected_layers.cmake | 7 ++ 4 files changed, 184 insertions(+) create mode 100644 platforms/nuttx/src/px4/common/board_ctrl.c create mode 100644 platforms/nuttx/src/px4/common/include/px4_platform/board_ctrl.h diff --git a/platforms/nuttx/src/px4/common/board_ctrl.c b/platforms/nuttx/src/px4/common/board_ctrl.c new file mode 100644 index 0000000000..7ebc942c79 --- /dev/null +++ b/platforms/nuttx/src/px4/common/board_ctrl.c @@ -0,0 +1,104 @@ +/**************************************************************************** + * + * Copyright (C) 2020 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. + * + ****************************************************************************/ + +/** + * @file board_ctrl.c + * + * Provide a kernel-userspace boardctl_ioctl interface + */ + +#include +#include +#include +#include "board_config.h" + +static struct { + ioctl_ptr_t ioctl_func; +} ioctl_ptrs[MAX_IOCTL_PTRS]; + +/************************************************************************************ + * Name: px4_register_boardct_ioctl + * + * Description: + * an interface function for kernel services to register an ioct handler for user side + * + ************************************************************************************/ + + +int px4_register_boardct_ioctl(unsigned base, ioctl_ptr_t func) +{ + unsigned i = IOCTL_BASE_TO_IDX(base); + int ret = PX4_ERROR; + + if (i < MAX_IOCTL_PTRS) { + ioctl_ptrs[i].ioctl_func = func; + ret = PX4_OK; + } + + return ret; +} + +/************************************************************************************ + * Name: board_ioctl + * + * Description: + * implements board_ioctl for userspace-kernel interface + * + ************************************************************************************/ + +int board_ioctl(unsigned int cmd, uintptr_t arg) +{ + unsigned i = IOCTL_BASE_TO_IDX(cmd); + int ret = -EINVAL; + + if (i < MAX_IOCTL_PTRS && ioctl_ptrs[i].ioctl_func) { + ret = ioctl_ptrs[i].ioctl_func(cmd, arg); + } + + return ret; +} + +/************************************************************************************ + * Name: kernel_ioctl_initialize + * + * Description: + * initializes the kernel-side ioctl interface + * + ************************************************************************************/ + +void kernel_ioctl_initialize(void) +{ + for (int i = 0; i < MAX_IOCTL_PTRS; i++) { + ioctl_ptrs[i].ioctl_func = NULL; + } +} diff --git a/platforms/nuttx/src/px4/common/include/px4_platform/board_ctrl.h b/platforms/nuttx/src/px4/common/include/px4_platform/board_ctrl.h new file mode 100644 index 0000000000..686402989e --- /dev/null +++ b/platforms/nuttx/src/px4/common/include/px4_platform/board_ctrl.h @@ -0,0 +1,63 @@ +/**************************************************************************** + * + * Copyright (C) 2020 Technology Innovation Institute. All rights reserved. + * Author: Jukka Laitinen + * + * 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 + +/* Encode the px4 boardctl ioctls in the following way: + * the highest 4-bits identifies the boardctl's used by this if + * the next 4-bits identifies the module which handles the ioctl + * the low byte identiefies the actual IOCTL within the module + */ + +#define _BOARDCTLIOCBASE (0x4000) +#define IOCTL_IDX_TO_BASE(x) ((((x) & 0xF) << 8) | _BOARDCTLIOCBASE) +#define IOCTL_BASE_TO_IDX(x) (((x) & 0x0F00) >> 8) + +#define _ORBIOCDEVBASE IOCTL_IDX_TO_BASE(0) +#define _HRTIOCBASE IOCTL_IDX_TO_BASE(1) +#define _CRYPTOIOCBASE IOCTL_IDX_TO_BASE(2) +#define _BUILTINIOCBASE IOCTL_IDX_TO_BASE(3) +#define MAX_IOCTL_PTRS 4 + +typedef int (*ioctl_ptr_t)(unsigned int, unsigned long); + +__BEGIN_DECLS + +/* Function to initialize or reset the interface */ +void kernel_ioctl_initialize(void); + +/* Function to register a px4 boardctl handler */ +int px4_register_boardct_ioctl(unsigned base, ioctl_ptr_t func); + +__END_DECLS diff --git a/platforms/nuttx/src/px4/common/px4_init.cpp b/platforms/nuttx/src/px4/common/px4_init.cpp index e7f0ee5723..7a18ceb7e1 100644 --- a/platforms/nuttx/src/px4/common/px4_init.cpp +++ b/platforms/nuttx/src/px4/common/px4_init.cpp @@ -56,11 +56,21 @@ #include #endif +#if !defined(CONFIG_BUILD_FLAT) +#include +#endif + extern void cdcacm_init(void); int px4_platform_init() { +#if !defined(CONFIG_BUILD_FLAT) + /* initialize userspace-kernelspace call gate interface */ + + kernel_ioctl_initialize(); +#endif + int ret = px4_console_buffer_init(); if (ret < 0) { diff --git a/platforms/nuttx/src/px4/common/px4_protected_layers.cmake b/platforms/nuttx/src/px4/common/px4_protected_layers.cmake index 91edc74073..95599eba82 100644 --- a/platforms/nuttx/src/px4/common/px4_protected_layers.cmake +++ b/platforms/nuttx/src/px4/common/px4_protected_layers.cmake @@ -18,6 +18,13 @@ target_link_libraries(px4_layer nuttx_mm ) +# Build the interface library between user and kernel side +add_library(px4_board_ctrl + board_ctrl.c +) + +add_dependencies(px4_board_ctrl nuttx_context px4_kernel_builtin_list_target) + # Build the kernel side px4_kernel_layer add_library(px4_kernel_layer