src/lib/paramters: Add a new interface library for protected build user side

Implement an interface for protected build to access parameters.

The implementation only does IOCTL calls to the kernel, where the parameters
live.

Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
This commit is contained in:
Jukka Laitinen 2021-11-09 08:54:10 +02:00 committed by Beat Küng
parent 41a7ae3db2
commit 0d31aadcc3
9 changed files with 613 additions and 9 deletions

View File

@ -412,6 +412,7 @@ endif()
# subdirectories
#
add_library(parameters_interface INTERFACE)
add_library(kernel_parameters_interface INTERFACE)
include(px4_add_library)
add_subdirectory(src/lib EXCLUDE_FROM_ALL)
@ -434,7 +435,13 @@ add_subdirectory(src/lib/metadata EXCLUDE_FROM_ALL)
# must be the last module before firmware
add_subdirectory(src/lib/parameters EXCLUDE_FROM_ALL)
if(${PX4_PLATFORM} STREQUAL "nuttx" AND NOT CONFIG_BUILD_FLAT)
target_link_libraries(parameters_interface INTERFACE usr_parameters)
target_link_libraries(kernel_parameters_interface INTERFACE parameters)
else()
target_link_libraries(parameters_interface INTERFACE parameters)
endif()
# firmware added last to generate the builtin for included modules
add_subdirectory(platforms/${PX4_PLATFORM})

View File

@ -166,12 +166,12 @@ function(px4_add_module)
endif()
if(NOT DYNAMIC)
target_link_libraries(${MODULE} PRIVATE prebuild_targets parameters_interface px4_platform systemlib perf)
target_link_libraries(${MODULE} PRIVATE prebuild_targets px4_platform systemlib perf)
if (${PX4_PLATFORM} STREQUAL "nuttx" AND NOT CONFIG_BUILD_FLAT AND KERNEL)
target_link_libraries(${MODULE} PRIVATE px4_kernel_layer uORB_kernel)
target_link_libraries(${MODULE} PRIVATE kernel_parameters_interface px4_kernel_layer uORB_kernel)
set_property(GLOBAL APPEND PROPERTY PX4_KERNEL_MODULE_LIBRARIES ${MODULE})
else()
target_link_libraries(${MODULE} PRIVATE px4_layer uORB)
target_link_libraries(${MODULE} PRIVATE parameters_interface px4_layer uORB)
set_property(GLOBAL APPEND PROPERTY PX4_MODULE_LIBRARIES ${MODULE})
endif()
set_property(GLOBAL APPEND PROPERTY PX4_MODULE_PATHS ${CMAKE_CURRENT_SOURCE_DIR})

View File

@ -47,8 +47,9 @@
#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
#define _PARAMIOCBASE IOCTL_IDX_TO_BASE(3)
#define _BUILTINIOCBASE IOCTL_IDX_TO_BASE(4)
#define MAX_IOCTL_PTRS 5
/* The BUILTINIOCLAUNCH IOCTL is used to launch kernel side modules
* from the user side code

View File

@ -150,6 +150,7 @@ add_custom_command(OUTPUT px4_parameters.hpp
set(SRCS)
list(APPEND SRCS parameters.cpp)
if(BUILD_TESTING)
list(APPEND SRCS param_translation_unit_tests.cpp)
else()
@ -158,6 +159,14 @@ endif()
if(${PX4_PLATFORM} STREQUAL "nuttx")
add_subdirectory(flashparams)
# build user-side interface for protected build
if(NOT CONFIG_BUILD_FLAT)
list(APPEND SRCS parameters_ioctl.cpp)
add_library(usr_parameters usr_parameters_if.cpp px4_parameters.hpp)
add_dependencies(usr_parameters prebuild_targets)
target_compile_definitions(usr_parameters PRIVATE -DMODULE_NAME="usr_parameters")
endif()
endif()
# TODO: find a better way to do this
@ -169,7 +178,7 @@ if (NOT "${PX4_BOARD}" MATCHES "px4_io")
target_link_libraries(parameters PRIVATE perf tinybson px4_platform)
target_compile_definitions(parameters PRIVATE -DMODULE_NAME="parameters")
target_compile_definitions(parameters PRIVATE -DMODULE_NAME="parameters" -D__KERNEL__)
target_compile_options(parameters
PRIVATE
#-DDEBUG_BUILD
@ -181,8 +190,8 @@ else()
endif()
add_dependencies(parameters prebuild_targets)
if(${PX4_PLATFORM} STREQUAL "nuttx" AND CONFIG_BUILD_FLAT)
target_link_libraries(parameters PRIVATE flashparams tinybson)
if(${PX4_PLATFORM} STREQUAL "nuttx")
target_link_libraries(parameters PRIVATE flashparams)
endif()
px4_add_functional_gtest(SRC ParameterTest.cpp LINKLIBS parameters)

View File

@ -72,6 +72,11 @@ using namespace time_literals;
/* Include functions common to user and kernel sides */
#include "parameters_common.cpp"
#if defined(__PX4_NUTTX) && !defined(CONFIG_BUILD_FLAT)
#include <px4_platform/board_ctrl.h>
#include "parameters_ioctl.h"
#endif
#if defined(FLASH_BASED_PARAMS)
#include "flashparams/flashparams.h"
#else
@ -192,6 +197,10 @@ param_init()
param_find_perf = perf_alloc(PC_COUNT, "param: find");
param_get_perf = perf_alloc(PC_COUNT, "param: get");
param_set_perf = perf_alloc(PC_ELAPSED, "param: set");
#if defined(__PX4_NUTTX) && !defined(CONFIG_BUILD_FLAT)
px4_register_boardct_ioctl(_PARAMIOCBASE, param_ioctl);
#endif
}
/**

View File

@ -0,0 +1,196 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
/**
* @file parameters_ioctl.cpp
*
* Protected build kernel space interface to global parameter store.
*/
#define PARAM_IMPLEMENTATION
#include "param.h"
#include "parameters_ioctl.h"
#include <px4_platform_common/defines.h>
int param_ioctl(unsigned int cmd, unsigned long arg)
{
int ret = OK;
switch (cmd) {
case PARAMIOCNOTIFY: {
param_notify_changes();
}
break;
case PARAMIOCFIND: {
paramiocfind_t *data = (paramiocfind_t *)arg;
if (data->notification) {
data->ret = param_find(data->name);
} else {
data->ret = param_find_no_notification(data->name);
}
}
break;
case PARAMIOCCOUNTUSED: {
paramioccountused_t *data = (paramioccountused_t *)arg;
data->ret = param_count_used();
}
break;
case PARAMIOCFORUSEDINDEX: {
paramiocforusedindex_t *data = (paramiocforusedindex_t *)arg;
data->ret = param_for_used_index(data->index);
}
break;
case PARAMIOCGETUSEDINDEX: {
paramiocgetusedindex_t *data = (paramiocgetusedindex_t *)arg;
data->ret = param_get_used_index(data->param);
}
break;
case PARAMIOCUNSAVED: {
paramiocunsaved_t *data = (paramiocunsaved_t *)arg;
data->ret = param_value_unsaved(data->param);
}
break;
case PARAMIOCGET: {
paramiocget_t *data = (paramiocget_t *)arg;
if (data->deflt) {
data->ret = param_get_default_value(data->param, data->val);
} else {
data->ret = param_get(data->param, data->val);
}
}
break;
case PARAMIOCAUTOSAVE: {
paramiocautosave_t *data = (paramiocautosave_t *)arg;
param_control_autosave(data->enable);
}
break;
case PARAMIOCSET: {
paramiocset_t *data = (paramiocset_t *)arg;
if (data->notification) {
data->ret = param_set(data->param, data->val);
} else {
data->ret = param_set_no_notification(data->param, data->val);
}
}
break;
case PARAMIOCUSED: {
paramiocused_t *data = (paramiocused_t *)arg;
data->ret = param_used(data->param);
}
break;
case PARAMIOCSETUSED: {
paramiocsetused_t *data = (paramiocsetused_t *)arg;
param_set_used(data->param);
}
break;
case PARAMIOCSETDEFAULT: {
paramiocsetdefault_t *data = (paramiocsetdefault_t *)arg;
data->ret = param_set_default_value(data->param, data->val);
}
break;
case PARAMIOCRESET: {
paramiocreset_t *data = (paramiocreset_t *)arg;
if (data->notification) {
data->ret = param_reset(data->param);
} else {
data->ret = param_reset_no_notification(data->param);
}
}
break;
case PARAMIOCRESETGROUP: {
paramiocresetgroup_t *data = (paramiocresetgroup_t *)arg;
if (data->type == PARAM_RESET_EXCLUDES) {
param_reset_excludes(data->group, data->num_in_group);
} else if (data->type == PARAM_RESET_SPECIFIC) {
param_reset_specific(data->group, data->num_in_group);
} else {
param_reset_all();
}
}
break;
case PARAMIOCSAVEDEFAULT: {
paramiocsavedefault_t *data = (paramiocsavedefault_t *)arg;
data->ret = param_save_default();
}
break;
case PARAMIOCLOADDEFAULT: {
paramiocloaddefault_t *data = (paramiocloaddefault_t *)arg;
data->ret = param_load_default();
}
break;
case PARAMIOCEXPORT: {
paramiocexport_t *data = (paramiocexport_t *)arg;
data->ret = param_export(data->filename, nullptr);
}
break;
case PARAMIOCHASH: {
paramiochash_t *data = (paramiochash_t *)arg;
data->ret = param_hash_check();
}
break;
default:
ret = -ENOTTY;
break;
}
return ret;
}

View File

@ -0,0 +1,162 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
/**
* @file parameters_ioctl.h
*
* User space - kernel space interface to global parameter store.
*/
#pragma once
#define PARAM_IMPLEMENTATION
#include "param.h"
#include <px4_platform/board_ctrl.h>
#define _PARAMIOC(_n) (_PX4_IOC(_PARAMIOCBASE, _n))
#define PARAMIOCNOTIFY _PARAMIOC(1)
#define PARAMIOCFIND _PARAMIOC(2)
typedef struct paramiocfind {
const char *name;
const bool notification;
param_t ret;
} paramiocfind_t;
#define PARAMIOCCOUNTUSED _PARAMIOC(3)
typedef struct paramioccountused {
unsigned ret;
} paramioccountused_t;
#define PARAMIOCFORUSEDINDEX _PARAMIOC(4)
typedef struct paramiocforusedindex {
const unsigned index;
param_t ret;
} paramiocforusedindex_t;
#define PARAMIOCGETUSEDINDEX _PARAMIOC(5)
typedef struct paramiocgetusedindex {
const param_t param;
unsigned ret;
} paramiocgetusedindex_t;
#define PARAMIOCUNSAVED _PARAMIOC(6)
typedef struct paramiocunsaved {
const param_t param;
bool ret;
} paramiocunsaved_t;
#define PARAMIOCGET _PARAMIOC(7)
typedef struct paramiocget {
const param_t param;
const bool deflt;
void *const val;
int ret;
} paramiocget_t;
#define PARAMIOCAUTOSAVE _PARAMIOC(8)
typedef struct paramiocautosave {
const bool enable;
} paramiocautosave_t;
#define PARAMIOCSET _PARAMIOC(9)
typedef struct paramiocset {
const param_t param;
const bool notification;
const void *val;
int ret;
} paramiocset_t;
#define PARAMIOCUSED _PARAMIOC(10)
typedef struct paramiocused {
const param_t param;
bool ret;
} paramiocused_t;
#define PARAMIOCSETUSED _PARAMIOC(11)
typedef struct paramiocsetused {
const param_t param;
} paramiocsetused_t;
#define PARAMIOCSETDEFAULT _PARAMIOC(12)
typedef struct paramiocsetdefault {
const param_t param;
const void *val;
int ret;
} paramiocsetdefault_t;
#define PARAMIOCRESET _PARAMIOC(13)
typedef struct paramiocreset {
const param_t param;
const bool notification;
int ret;
} paramiocreset_t;
#define PARAMIOCRESETGROUP _PARAMIOC(14)
typedef enum {
PARAM_RESET_ALL,
PARAM_RESET_EXCLUDES,
PARAM_RESET_SPECIFIC
} param_reset_type_t;
typedef struct paramiocresetgroup {
param_reset_type_t type;
const char **group;
const int num_in_group;
} paramiocresetgroup_t;
#define PARAMIOCSAVEDEFAULT _PARAMIOC(15)
typedef struct paramiocsavedefault {
int ret;
} paramiocsavedefault_t;
#define PARAMIOCLOADDEFAULT _PARAMIOC(16)
typedef struct paramiocloaddefault {
int ret;
} paramiocloaddefault_t;
#define PARAMIOCEXPORT _PARAMIOC(17)
typedef struct paramiocexport {
const char *filename;
int ret;
} paramiocexport_t;
#define PARAMIOCHASH _PARAMIOC(18)
typedef struct paramiochash {
uint32_t ret;
} paramiochash_t;
int param_ioctl(unsigned int cmd, unsigned long arg);

View File

@ -0,0 +1,220 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
/**
* @file usr_parameters_if.cpp
*
* Protected build user space interface to global parameter store.
*/
#define PARAM_IMPLEMENTATION
#include "param.h"
#include "parameters_ioctl.h"
#include <parameters/px4_parameters.hpp>
#include <sys/boardctl.h>
#include <px4_platform_common/defines.h>
#include "parameters_common.cpp"
void
param_notify_changes()
{
boardctl(PARAMIOCNOTIFY, NULL);
}
param_t param_find(const char *name)
{
paramiocfind_t data = {name, true, PARAM_INVALID};
boardctl(PARAMIOCFIND, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
param_t param_find_no_notification(const char *name)
{
paramiocfind_t data = {name, false, PARAM_INVALID};
boardctl(PARAMIOCFIND, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
unsigned param_count_used()
{
paramioccountused_t data = {0};
boardctl(PARAMIOCCOUNTUSED, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
param_t param_for_used_index(unsigned index)
{
paramiocforusedindex_t data = {index, 0};
boardctl(PARAMIOCFORUSEDINDEX, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int param_get_used_index(param_t param)
{
paramiocgetusedindex_t data = {param, 0};
boardctl(PARAMIOCGETUSEDINDEX, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
bool
param_value_unsaved(param_t param)
{
paramiocunsaved_t data = {param, false};
boardctl(PARAMIOCUNSAVED, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_get(param_t param, void *val)
{
paramiocget_t data = {param, false, val, PX4_ERROR};
boardctl(PARAMIOCGET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_get_default_value(param_t param, void *default_val)
{
paramiocget_t data = {param, true, default_val, PX4_ERROR};
boardctl(PARAMIOCGET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
void
param_control_autosave(bool enable)
{
paramiocautosave_t data = {enable};
boardctl(PARAMIOCAUTOSAVE, reinterpret_cast<unsigned long>(&data));
}
int param_set(param_t param, const void *val)
{
paramiocset_t data = {param, true, val, PX4_ERROR};
boardctl(PARAMIOCSET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int param_set_no_notification(param_t param, const void *val)
{
paramiocset_t data = {param, false, val, PX4_ERROR};
boardctl(PARAMIOCSET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
bool param_used(param_t param)
{
paramiocused_t data = {param, false};
boardctl(PARAMIOCUSED, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
void param_set_used(param_t param)
{
paramiocsetused_t data = {param};
boardctl(PARAMIOCSETUSED, reinterpret_cast<unsigned long>(&data));
}
int param_set_default_value(param_t param, const void *val)
{
paramiocsetdefault_t data = {param, val, PX4_ERROR};
boardctl(PARAMIOCSETDEFAULT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int param_reset(param_t param)
{
paramiocreset_t data = {param, true, PX4_ERROR};
boardctl(PARAMIOCRESET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int param_reset_no_notification(param_t param)
{
paramiocreset_t data = {param, false, PX4_ERROR};
boardctl(PARAMIOCRESET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
void
param_reset_all()
{
paramiocresetgroup_t data = {PARAM_RESET_ALL, nullptr, 0};
boardctl(PARAMIOCRESETGROUP, reinterpret_cast<unsigned long>(&data));
}
void
param_reset_excludes(const char *excludes[], int num_excludes)
{
paramiocresetgroup_t data = {PARAM_RESET_EXCLUDES, excludes, num_excludes};
boardctl(PARAMIOCRESETGROUP, reinterpret_cast<unsigned long>(&data));
}
void
param_reset_specific(const char *resets[], int num_resets)
{
paramiocresetgroup_t data = {PARAM_RESET_SPECIFIC, resets, num_resets};
boardctl(PARAMIOCRESETGROUP, reinterpret_cast<unsigned long>(&data));
}
int param_save_default()
{
paramiocsavedefault_t data = {PX4_ERROR};
boardctl(PARAMIOCSAVEDEFAULT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_load_default()
{
paramiocloaddefault_t data = {PX4_ERROR};
boardctl(PARAMIOCLOADDEFAULT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_export(const char *filename, param_filter_func filter)
{
paramiocexport_t data = {filename, PX4_ERROR};
if (filter) { PX4_ERR("ERROR: filter not supported in userside blob"); }
boardctl(PARAMIOCEXPORT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
uint32_t param_hash_check()
{
paramiochash_t data = {0};
boardctl(PARAMIOCHASH, reinterpret_cast<unsigned long>(&data));
return data.ret;
}

View File

@ -42,4 +42,4 @@ px4_add_library(sensor_calibration
Utilities.hpp
)
target_link_libraries(sensor_calibration PRIVATE conversion parameters)
target_link_libraries(sensor_calibration PRIVATE conversion)