initial minimal PX4_ROS2 platform and px4_ros2_default build (#20689)

- new ROS2 platform in PX4 intended for creating configs that build and run entirely in ROS2
 - PX4_CONFIG defaults to px4_ros2_default if no config specified and in a colcon workspace with ROS_VERSION=2
 - currently doesn't do much other than allow you to build px4 msgs interface package
This commit is contained in:
Daniel Agar 2022-12-08 23:03:44 -05:00 committed by GitHub
parent cfb670fbb3
commit 8114aad983
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
73 changed files with 4037 additions and 247 deletions

View File

@ -133,6 +133,5 @@
"workbench.settings.enableNaturalLanguageSearch": false,
"yaml.schemas": {
"${workspaceFolder}/validation/module_schema.yaml": "${workspaceFolder}/src/modules/*/module.yaml"
},
"cortex-debug.openocdPath": "${env:PICO_SDK_PATH}/../openocd/src/openocd" // Added for rp2040
}
}

View File

@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2017 - 2019 PX4 Development Team. All rights reserved.
# Copyright (c) 2017 - 2022 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@ -143,25 +143,17 @@ define_property(GLOBAL PROPERTY PX4_SRC_FILES
# configuration
#
set(CONFIG "px4_sitl_default" CACHE STRING "desired configuration")
include(px4_add_module)
set(config_module_list)
set(config_kernel_list)
# Find Python
# If using catkin, Python 2 is found since it points
# to the Python libs installed with the ROS distro
if (NOT CATKIN_DEVEL_PREFIX)
find_package(PythonInterp 3)
# We have a custom error message to tell users how to install python3.
if (NOT PYTHONINTERP_FOUND)
message(FATAL_ERROR "Python 3 not found. Please install Python 3:\n"
" Ubuntu: sudo apt install python3 python3-dev python3-pip\n"
" macOS: brew install python")
endif()
else()
find_package(PythonInterp REQUIRED)
find_package(PythonInterp 3)
# We have a custom error message to tell users how to install python3.
if(NOT PYTHONINTERP_FOUND)
message(FATAL_ERROR "Python 3 not found. Please install Python 3:\n"
" Ubuntu: sudo apt install python3 python3-dev python3-pip\n"
" macOS: brew install python")
endif()
option(PYTHON_COVERAGE "Python code coverage" OFF)
@ -207,6 +199,11 @@ if(EXISTS "${PX4_SOURCE_DIR}/platforms/${PX4_PLATFORM}/cmake/init.cmake")
include(init)
endif()
#=============================================================================
# project definition
#
project(px4 CXX C ASM)
# CMake build type (Debug Release RelWithDebInfo MinSizeRel Coverage)
if(NOT CMAKE_BUILD_TYPE)
if(${PX4_PLATFORM} STREQUAL "nuttx")
@ -235,11 +232,6 @@ endif()
set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug;Release;RelWithDebInfo;MinSizeRel;Coverage;AddressSanitizer;UndefinedBehaviorSanitizer")
message(STATUS "cmake build type: ${CMAKE_BUILD_TYPE}")
#=============================================================================
# project definition
#
project(px4 CXX C ASM)
# Check if LTO option and check if toolchain supports it
if(LTO)
include(CheckIPOSupported)
@ -256,15 +248,9 @@ set(CMAKE_C_STANDARD 11)
set(CMAKE_C_STANDARD_REQUIRED ON)
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
# For the catkin build process, unset build of dynamically-linked binaries
# and do not change CMAKE_RUNTIME_OUTPUT_DIRECTORY
if (NOT CATKIN_DEVEL_PREFIX)
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PX4_BINARY_DIR})
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_DEBUG ${PX4_BINARY_DIR})
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_RELEASE ${PX4_BINARY_DIR})
else()
SET(BUILD_SHARED_LIBS OFF)
endif()
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PX4_BINARY_DIR})
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_DEBUG ${PX4_BINARY_DIR})
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_RELEASE ${PX4_BINARY_DIR})
#=============================================================================
@ -309,21 +295,6 @@ endif()
include(ccache)
#=============================================================================
# find programs and packages
#
# see if catkin was invoked to build this
if (CATKIN_DEVEL_PREFIX)
message(STATUS "catkin ENABLED")
find_package(catkin REQUIRED)
if (catkin_FOUND)
catkin_package()
else()
message(FATAL_ERROR "catkin not found")
endif()
endif()
#=============================================================================
# get chip and chip manufacturer
#
@ -450,10 +421,10 @@ add_subdirectory(src/lib/metadata EXCLUDE_FROM_ALL)
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)
target_link_libraries(parameters_interface INTERFACE usr_parameters)
target_link_libraries(kernel_parameters_interface INTERFACE parameters)
else()
target_link_libraries(parameters_interface INTERFACE parameters)
target_link_libraries(parameters_interface INTERFACE parameters)
endif()
# firmware added last to generate the builtin for included modules
@ -486,17 +457,13 @@ include(doxygen)
include(metadata)
include(package)
# print size
add_custom_target(size
COMMAND size $<TARGET_FILE:px4>
DEPENDS px4
WORKING_DIRECTORY ${PX4_BINARY_DIR}
USES_TERMINAL
)
# install python requirements using configured python
add_custom_target(install_python_requirements
COMMAND ${PYTHON_EXECUTABLE} -m pip install --requirement ${PX4_SOURCE_DIR}/Tools/setup/requirements.txt
DEPENDS ${PX4_SOURCE_DIR}/Tools/setup/requirements.txt
USES_TERMINAL
)
if(EXISTS "${PX4_SOURCE_DIR}/platforms/${PX4_PLATFORM}/cmake/finalize.cmake")
include(finalize)
endif()

View File

@ -17,6 +17,8 @@ menu "Toolchain"
bool "posix"
config PLATFORM_QURT
bool "qurt"
config PLATFORM_ROS2
bool "ros2"
endchoice
config BOARD_PLATFORM
@ -24,6 +26,7 @@ menu "Toolchain"
default "nuttx" if PLATFORM_NUTTX
default "posix" if PLATFORM_POSIX
default "qurt" if PLATFORM_QURT
default "ros2" if PLATFORM_ROS2
config BOARD_LOCKSTEP
bool "Force enable lockstep"

View File

@ -0,0 +1 @@
CONFIG_PLATFORM_ROS2=y

View File

@ -0,0 +1,36 @@
############################################################################
#
# Copyright (c) 2022 PX4 Development Team. 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.
#
############################################################################
add_library(drivers_board
init.cpp
)

View File

@ -1,7 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
* Copyright (c) 2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -33,25 +32,19 @@
****************************************************************************/
/**
* @file conversions.c
* Implementation of commonly used conversions.
* @file board_config.h
*
* SITL internal definitions
*/
#include <px4_platform_common/px4_config.h>
#include <float.h>
#pragma once
#include "conversions.h"
#define BOARD_OVERRIDE_UUID "SIMULATIONID0000" // must be of length 16
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_SITL
int16_t
int16_t_from_bytes(uint8_t bytes[])
{
union {
uint8_t b[2];
int16_t w;
} u;
#define BOARD_HAS_POWER_CONTROL 1
u.b[1] = bytes[0];
u.b[0] = bytes[1];
#define BOARD_NUMBER_BRICKS 0
return u.w;
}
#include <system_config.h>
#include <px4_platform_common/board_common.h>

View File

View File

@ -57,4 +57,7 @@ else()
endif()
include(CPack)
include(bloaty)
if(${PX4_PLATFORM} MATCHES "nuttx")
include(bloaty)
endif()

View File

@ -155,9 +155,6 @@ function(px4_add_common_flags)
# CXX only flags
set(cxx_flags)
list(APPEND cxx_flags
-fno-exceptions
-fno-threadsafe-statics
-Wreorder
# disabled warnings

View File

@ -39,7 +39,9 @@ include(px4_list_make_absolute)
# Like add_library but with PX4 platform dependencies
#
function(px4_add_library target)
add_library(${target} EXCLUDE_FROM_ALL ${ARGN})
add_library(${target} STATIC EXCLUDE_FROM_ALL
${ARGN}
)
target_compile_definitions(${target} PRIVATE MODULE_NAME="${target}")

View File

@ -33,6 +33,16 @@
# find PX4 config
# look for in tree board config that matches CONFIG input
if(NOT CONFIG)
# default to px4_ros2_default if building within a ROS2 colcon environment
if(("$ENV{COLCON}" MATCHES "1") AND ("$ENV{ROS_VERSION}" MATCHES "2"))
set(CONFIG "px4_ros2_default" CACHE STRING "desired configuration")
else()
set(CONFIG "px4_sitl_default" CACHE STRING "desired configuration")
endif()
endif()
if(NOT PX4_CONFIG_FILE)
file(GLOB_RECURSE board_configs
@ -40,8 +50,6 @@ if(NOT PX4_CONFIG_FILE)
"boards/*.px4board"
)
set(PX4_CONFIGS ${board_configs} CACHE STRING "PX4 board configs" FORCE)
foreach(filename ${board_configs})
# parse input CONFIG into components to match with existing in tree configs
# the platform prefix (eg nuttx_) is historical, and removed if present
@ -63,9 +71,9 @@ if(NOT PX4_CONFIG_FILE)
)
set(PX4_CONFIG_FILE "${PX4_SOURCE_DIR}/boards/${filename}" CACHE FILEPATH "path to PX4 CONFIG file" FORCE)
set(PX4_BOARD_DIR "${PX4_SOURCE_DIR}/boards/${vendor}/${model}" CACHE STRING "PX4 board directory" FORCE)
set(MODEL "${model}" CACHE STRING "PX4 board model" FORCE)
set(VENDOR "${vendor}" CACHE STRING "PX4 board vendor" FORCE)
set(LABEL "${label}" CACHE STRING "PX4 board vendor" FORCE)
set(MODEL "${model}" CACHE STRING "PX4 board model" FORCE)
set(VENDOR "${vendor}" CACHE STRING "PX4 board vendor" FORCE)
set(LABEL "${label}" CACHE STRING "PX4 board vendor" FORCE)
break()
endif()
@ -76,19 +84,15 @@ if(NOT PX4_CONFIG_FILE)
)
set(PX4_CONFIG_FILE "${PX4_SOURCE_DIR}/boards/${filename}" CACHE FILEPATH "path to PX4 CONFIG file" FORCE)
set(PX4_BOARD_DIR "${PX4_SOURCE_DIR}/boards/${vendor}/${model}" CACHE STRING "PX4 board directory" FORCE)
set(MODEL "${model}" CACHE STRING "PX4 board model" FORCE)
set(VENDOR "${vendor}" CACHE STRING "PX4 board vendor" FORCE)
set(LABEL "${label}" CACHE STRING "PX4 board vendor" FORCE)
set(MODEL "${model}" CACHE STRING "PX4 board model" FORCE)
set(VENDOR "${vendor}" CACHE STRING "PX4 board vendor" FORCE)
set(LABEL "${label}" CACHE STRING "PX4 board vendor" FORCE)
break()
endif()
endif()
endforeach()
endif()
if(NOT PX4_CONFIG_FILE)
message(FATAL_ERROR "PX4 config file not set, try one of ${PX4_CONFIGS}")
endif()
message(STATUS "PX4 config file: ${PX4_CONFIG_FILE}")
include_directories(${PX4_BOARD_DIR}/src)
@ -108,9 +112,9 @@ set(PX4_BOARD_LABEL ${LABEL} CACHE STRING "PX4 board label" FORCE)
set(PX4_CONFIG "${PX4_BOARD_VENDOR}_${PX4_BOARD_MODEL}_${PX4_BOARD_LABEL}" CACHE STRING "PX4 config" FORCE)
if(EXISTS "${PX4_BOARD_DIR}/uavcan_board_identity")
include ("${PX4_BOARD_DIR}/uavcan_board_identity")
include ("${PX4_BOARD_DIR}/uavcan_board_identity")
endif()
if(EXISTS "${PX4_BOARD_DIR}/sitl.cmake")
include ("${PX4_BOARD_DIR}/sitl.cmake")
include ("${PX4_BOARD_DIR}/sitl.cmake")
endif()

View File

@ -1,66 +1,27 @@
<?xml version="1.0"?>
<package>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>px4</name>
<version>1.0.0</version>
<description>The PX4 Flight Stack package</description>
<version>1.14.0</version>
<description>PX4 Autopilot</description>
<maintainer email="daniel@agar.ca">dagar</maintainer>
<license>BSD 3</license>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="lorenz@px4.io">Lorenz Meier</maintainer>
<build_depend>rosidl_default_generators</build_depend>
<buildtool_depend>ament_cmake</buildtool_depend>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>BSD</license>
<depend>rclcpp</depend>
<depend>std_msgs</depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<!-- Url tags are optional, but mutiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<url type="website">http://px4.io/ros</url>
<member_of_group>rosidl_interface_packages</member_of_group>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<!-- Author tags are optional, mutiple are allowed, one per tag -->
<!-- Authors do not have to be maintianers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *_depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use build_depend for packages you need at compile time: -->
<build_depend>message_generation</build_depend>
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use run_depend for packages you need at runtime: -->
<run_depend>message_runtime</run_depend>
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>libmavconn</build_depend>
<build_depend>tf</build_depend>
<build_depend>rostest</build_depend>
<build_depend>mav_msgs</build_depend>
<run_depend>roscpp</run_depend>
<run_depend>rospy</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>libmavconn</run_depend>
<run_depend>tf</run_depend>
<run_depend>mav_msgs</run_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- You can specify that this package is a metapackage here: -->
<!-- <metapackage/> -->
<!-- Other tools can request additional information be placed here -->
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@ -40,7 +40,7 @@ if(NOT "${PX4_PLATFORM}" MATCHES "qurt" AND NOT "${PX4_BOARD}" MATCHES "io-v2" A
)
endif()
add_library(px4_platform
add_library(px4_platform STATIC
board_common.c
board_identity.c
events.cpp
@ -56,7 +56,7 @@ add_library(px4_platform
)
target_link_libraries(px4_platform prebuild_targets px4_work_queue)
if (NOT "${PX4_BOARD}" MATCHES "io-v2")
if(NOT "${PX4_BOARD}" MATCHES "io-v2")
add_subdirectory(uORB)
endif()

View File

@ -67,7 +67,7 @@ typedef int px4_task_t;
/** Default scheduler type */
#define SCHED_DEFAULT SCHED_FIFO
#if defined(__PX4_LINUX) || defined(__PX4_DARWIN) || defined(__PX4_CYGWIN)
#if defined(__PX4_LINUX) || defined(__PX4_DARWIN) || defined(__PX4_CYGWIN) || defined(__PX4_ROS2)
#define SCHED_PRIORITY_MAX sched_get_priority_max(SCHED_FIFO)
#define SCHED_PRIORITY_MIN sched_get_priority_min(SCHED_FIFO)

View File

@ -32,9 +32,9 @@
############################################################################
# nuttx uses internal work queue currently
if (NOT "${PX4_PLATFORM}" MATCHES "nuttx")
if(NOT "${PX4_PLATFORM}" MATCHES "nuttx")
add_library(work_queue
add_library(work_queue STATIC
dq_addlast.c
dq_rem.c
dq_remfirst.c

View File

@ -35,6 +35,7 @@
#include <stdio.h>
#include "work_lock.h"
#include <px4_platform_common/sem.h>
extern px4_sem_t _work_lock[];

View File

@ -64,10 +64,19 @@ function(px4_os_add_flags)
${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/apps/include
)
# prevent using the toolchain's std c++ library
add_compile_options($<$<COMPILE_LANGUAGE:CXX>:-nostdinc++>)
add_compile_options($<$<COMPILE_LANGUAGE:CXX>:-fno-sized-deallocation>)
set(cxx_flags)
list(APPEND cxx_flags
-fno-exceptions
-fno-rtti
-fno-sized-deallocation
-fno-threadsafe-statics
-nostdinc++ # prevent using the toolchain's std c++ library
)
foreach(flag ${cxx_flags})
add_compile_options($<$<COMPILE_LANGUAGE:CXX>:${flag}>)
endforeach()
add_compile_options($<$<COMPILE_LANGUAGE:C>:-Wbad-function-cast>)

View File

@ -53,7 +53,7 @@
#include <arch/board/board.h>
#include "flexcan.h"
#include <lib/systemlib/crc.h>
#include <lib/crc/crc.h>
#define CAN_TX_TIMEOUT_MS (200 /(1000/(1000000/CONFIG_USEC_PER_TICK)))

View File

@ -55,7 +55,7 @@
#include <arch/board/board.h>
#include <lib/systemlib/crc.h>
#include <lib/crc/crc.h>
#define INAK_TIMEOUT 65535

View File

@ -54,7 +54,7 @@
#include <arch/board/board.h>
#include <lib/systemlib/crc.h>
#include <lib/crc/crc.h>
#define INAK_TIMEOUT 65535

View File

@ -49,7 +49,7 @@
#include "uavcan.h"
#include "can.h"
#include <lib/systemlib/crc.h>
#include <lib/crc/crc.h>
#define CAN_REQUEST_TIMEOUT 1000
#define ANY_NODE_ID 0

View File

@ -58,7 +58,7 @@
#include <drivers/bootloaders/boot_app_shared.h>
#include <drivers/bootloaders/boot_alt_app_shared.h>
#include <drivers/drv_watchdog.h>
#include <lib/systemlib/crc.h>
#include <lib/crc/crc.h>
//#define DEBUG_APPLICATION_INPLACE 1 /* Never leave defined */
#define DEBUG_NO_FW_UPDATE 1 /* With DEBUG_APPLICATION_INPLACE

View File

@ -34,4 +34,4 @@
px4_add_library(arch_board_hw_info
board_hw_rev_ver.c
)
target_link_libraries(arch_board_hw_info PRIVATE arch_adc systemlib)
target_link_libraries(arch_board_hw_info PRIVATE arch_adc crc)

View File

@ -48,8 +48,8 @@
#include <fcntl.h>
#include <board_config.h>
#include <systemlib/crc.h>
#include <systemlib/px4_macros.h>
#include <lib/crc/crc.h>
#include <lib/systemlib/px4_macros.h>
#if defined(BOARD_HAS_HW_VERSIONING)

View File

@ -3,13 +3,9 @@ include_directories(${CMAKE_CURRENT_BINARY_DIR})
get_property(module_libraries GLOBAL PROPERTY PX4_MODULE_LIBRARIES)
# When building with catkin, do not change CMAKE_RUNTIME_OUTPUT_DIR from
# CMAKE_CURRENT_BINARY_DIR ''./platforms/posix' to './bin'
if (NOT CATKIN_DEVEL_PREFIX)
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin)
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_DEBUG ${CMAKE_BINARY_DIR}/bin)
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_RELEASE ${CMAKE_BINARY_DIR}/bin)
endif()
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin)
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_DEBUG ${CMAKE_BINARY_DIR}/bin)
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_RELEASE ${CMAKE_BINARY_DIR}/bin)
set(PX4_SHELL_COMMAND_PREFIX "px4-")

View File

@ -0,0 +1,78 @@
############################################################################
#
# Copyright (c) 2022 PX4 Development Team. 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.
#
############################################################################
#include_directories(${CMAKE_CURRENT_BINARY_DIR})
message(STATUS "ROS_VERSION: $ENV{ROS_VERSION}")
message(STATUS "AMENT_PREFIX_PATH: $ENV{AMENT_PREFIX_PATH}")
get_property(module_libraries GLOBAL PROPERTY PX4_MODULE_LIBRARIES)
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin)
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_DEBUG ${CMAKE_BINARY_DIR}/bin)
set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_RELEASE ${CMAKE_BINARY_DIR}/bin)
# add_executable(px4
# src/px4/common/main.cpp
# )
add_compile_options(
-Wno-error
-Wno-float-equal # msg generated equality operator
)
include_directories(${PX4_BINARY_DIR})
# relative path to msgs
set(ros_msg_files)
foreach(msg_file ${msg_files})
file(RELATIVE_PATH relative_path ${CMAKE_CURRENT_SOURCE_DIR} ${msg_file})
list(APPEND ros_msg_files ${relative_path})
endforeach()
rosidl_generate_interfaces(${PROJECT_NAME}
${ros_msg_files}
)
# # mc_rate_control_ros2
# add_executable(mc_rate_control ${CMAKE_SOURCE_DIR}/src/modules/mc_rate_control_ros2/MulticopterRateControl.cpp)
# target_link_libraries(mc_rate_control px4_layer work_queue)
# ament_target_dependencies(mc_rate_control rclcpp std_msgs)
# rosidl_target_interfaces(mc_rate_control ${PROJECT_NAME} "rosidl_typesupport_cpp")
# add_dependencies(mc_rate_control generate_parameters)
# install(
# TARGETS
# mc_rate_control
# DESTINATION lib/${PROJECT_NAME}
# )

View File

@ -0,0 +1,50 @@
############################################################################
#
# Copyright (c) 2022 PX4 Development Team. 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.
#
############################################################################
# compiler tools
foreach(tool nm ld)
string(TOUPPER ${tool} TOOL)
find_program(${TOOL} ${tool})
if(NOT ${TOOL})
message(FATAL_ERROR "could not find ${tool}")
endif()
endforeach()
# os tools
foreach(tool echo grep rm mkdir nm cp touch make unzip)
string(TOUPPER ${tool} TOOL)
find_program(${TOOL} ${tool})
if(NOT ${TOOL})
message(FATAL_ERROR "could not find ${TOOL}")
endif()
endforeach()

View File

@ -0,0 +1,34 @@
############################################################################
#
# Copyright (c) 2022 PX4 Development Team. 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.
#
############################################################################
ament_package()

View File

@ -0,0 +1,40 @@
############################################################################
#
# Copyright (c) 2022 PX4 Development Team. 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.
#
############################################################################
enable_language(CXX)
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(std_msgs REQUIRED)

View File

@ -0,0 +1,148 @@
############################################################################
#
# Copyright (c) 2022 PX4 Development Team. 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.
#
############################################################################
#=============================================================================
#
# Defined functions in this file
#
# OS Specific Functions
#
# * px4_posix_generate_builtin_commands
#
# Required OS Interface Functions
#
# * px4_os_add_flags
# * px4_os_determine_build_chip
# * px4_os_prebuild_targets
#
#=============================================================================
#
# px4_posix_generate_builtin_commands
#
# This function generates the builtin_commands.c src for posix
#
# Usage:
# px4_posix_generate_builtin_commands(
# MODULE_LIST <in-list>
# OUT <file>)
#
# Input:
# MODULE_LIST : list of modules
#
# Output:
# OUT : stem of generated apps.cpp/apps.h ("apps")
#
# Example:
# px4_posix_generate_builtin_commands(
# OUT <generated-src> MODULE_LIST px4_simple_app)
#
function(px4_posix_generate_builtin_commands)
px4_parse_function_args(
NAME px4_posix_generate_builtin_commands
ONE_VALUE OUT
MULTI_VALUE MODULE_LIST
REQUIRED MODULE_LIST OUT
ARGN ${ARGN})
endfunction()
#=============================================================================
#
# px4_os_add_flags
#
# Set the posix build flags.
#
# Usage:
# px4_os_add_flags()
#
function(px4_os_add_flags)
add_definitions(
-D__PX4_ROS2
-D__PX4_POSIX
-Dnoreturn_function=__attribute__\(\(noreturn\)\)
)
include_directories(platforms/ros2/include)
endfunction()
#=============================================================================
#
# px4_os_determine_build_chip
#
# Sets PX4_CHIP and PX4_CHIP_MANUFACTURER.
#
# Usage:
# px4_os_determine_build_chip()
#
function(px4_os_determine_build_chip)
# always use generic chip and chip manufacturer
set(PX4_CHIP "generic" CACHE STRING "PX4 Chip" FORCE)
set(PX4_CHIP_MANUFACTURER "generic" CACHE STRING "PX4 Chip Manufacturer" FORCE)
endfunction()
#=============================================================================
#
# px4_os_prebuild_targets
#
# This function generates os dependent targets
#
# Usage:
# px4_os_prebuild_targets(
# OUT <out-list_of_targets>
# BOARD <in-string>
# )
#
# Input:
# BOARD : board
#
# Output:
# OUT : the target list
#
# Example:
# px4_os_prebuild_targets(OUT target_list BOARD px4_fmu-v2)
#
function(px4_os_prebuild_targets)
px4_parse_function_args(
NAME px4_os_prebuild_targets
ONE_VALUE OUT BOARD
REQUIRED OUT
ARGN ${ARGN})
add_library(prebuild_targets INTERFACE)
endfunction()

View File

@ -1,7 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
* Author: Lorenz Meier <lm@inf.ethz.ch>
* Copyright (C) 2015 Mark Charlebois. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -32,30 +31,34 @@
*
****************************************************************************/
/**
* @file conversions.h
* Definition of commonly used conversions.
*
* Includes bit / byte / geo representation and unit conversions.
*/
#pragma once
#ifndef CONVERSIONS_H_
#define CONVERSIONS_H_
#include <float.h>
#include <stdint.h>
#include <px4_platform_common/posix.h>
#include <semaphore.h>
#include <px4_platform_common/workqueue.h>
#include <px4_platform_common/sem.h>
__BEGIN_DECLS
/**
* Converts a signed 16 bit integer from big endian to little endian.
*
* This function is for commonly used 16 bit big endian sensor data,
* delivered by driver routines as two 8 bit numbers in big endian order.
* Common vendors with big endian representation are Invense, Bosch and
* Honeywell. ST micro devices tend to use a little endian representation.
*/
__EXPORT int16_t int16_t_from_bytes(uint8_t bytes[]);
extern px4_sem_t _hrt_work_lock;
extern struct wqueue_s g_hrt_work;
void hrt_work_queue_init(void);
int hrt_work_queue(struct work_s *work, worker_t worker, void *arg, uint32_t usdelay);
void hrt_work_cancel(struct work_s *work);
static inline void hrt_work_lock(void);
static inline void hrt_work_lock()
{
px4_sem_wait(&_hrt_work_lock);
}
static inline void hrt_work_unlock(void);
static inline void hrt_work_unlock()
{
px4_sem_post(&_hrt_work_lock);
}
__END_DECLS
#endif /* CONVERSIONS_H_ */

View File

@ -0,0 +1,42 @@
#pragma once
#include "rclcpp/rclcpp.hpp"
namespace px4
{
class Node : public rclcpp::Node
{
public:
explicit Node(const char *node_name) :
rclcpp::Node(node_name)
{
}
~Node() override = default;
private:
};
};
// int main(int argc, char *argv[])
// {
// rclcpp::init(argc, argv);
// rclcpp::spin(std::make_shared<MulticopterRateControl>());
// rclcpp::shutdown();
// return 0;
// }
// #include "rclcpp_components/register_node_macro.hpp"
// // Register the component with class_loader.
// // This acts as a sort of entry point, allowing the component to be discoverable when its library
// // is being loaded into a running process.
// RCLCPP_COMPONENTS_REGISTER_NODE(composition::Client)

View File

@ -0,0 +1,53 @@
/****************************************************************************
*
* Copyright (c) 2014 PX4 Development Team. 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 defines.h
*
* Generally used magic defines
*/
#pragma once
/****************************************************************************
* Defines for all platforms.
****************************************************************************/
#define PX4_ERROR (-1)
#define PX4_OK 0
/* Define PX4_ISFINITE */
#ifdef __cplusplus
constexpr bool PX4_ISFINITE(float x) { return __builtin_isfinite(x); }
constexpr bool PX4_ISFINITE(double x) { return __builtin_isfinite(x); }
#endif /* __cplusplus */

View File

@ -0,0 +1,41 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. 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 <rclcpp/logging.hpp>
#define PX4_INFO(X) printf(X) //RCLCPP_INFO(get_logger(), X)
#define PX4_WARN(X) printf(X) //RCLCPP_WARN(get_logger(), X)
#define PX4_ERR(X) printf(X) //RCLCPP_ERR(get_logger(), X)
#define PX4_DEBUG(...) printf(X) //RCLCPP_DEBUG(get_logger(), __VA_ARGS__)

View File

@ -0,0 +1,417 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. 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 px4_module.h
*/
#pragma once
#ifdef __cplusplus
#include <cstring>
#include "rclcpp/rclcpp.hpp"
/**
* @class ModuleBase
* Base class for modules, implementing common functionality,
* such as 'start', 'stop' and 'status' commands.
* Currently does not support modules which allow multiple instances,
* such as mavlink.
*
* The class is implemented as curiously recurring template pattern (CRTP).
* It allows to have a static object in the base class that is different for
* each module type, and call static methods from the base class.
*
* @note Required methods for a derived class:
* When running in its own thread:
* static int task_spawn(int argc, char *argv[])
* {
* // call px4_task_spawn_cmd() with &run_trampoline as startup method
* // optional: wait until _object is not null, which means the task got initialized (use a timeout)
* // set _task_id and return 0
* // on error return != 0 (and _task_id must be -1)
* }
*
* static T *instantiate(int argc, char *argv[])
* {
* // this is called from within the new thread, from run_trampoline()
* // parse the arguments
* // create a new object T & return it
* // or return nullptr on error
* }
*
* static int custom_command(int argc, char *argv[])
* {
* // support for custom commands
* // it none are supported, just do:
* return print_usage("unrecognized command");
* }
*
* static int print_usage(const char *reason = nullptr)
* {
* // use the PRINT_MODULE_* methods...
* }
*
* When running on the work queue:
* - custom_command & print_usage as above
* static int task_spawn(int argc, char *argv[]) {
* // parse the arguments
* // set _object (here or from the work_queue() callback)
* // call work_queue() (with a custom cycle trampoline)
* // optional: wait until _object is not null, which means the task got initialized (use a timeout)
* // set _task_id to task_id_is_work_queue and return 0
* // on error return != 0 (and _task_id must be -1)
* }
*/
template<class T>
class ModuleBase : public rclcpp::Node
{
public:
ModuleBase() : Node(MODULE_NAME)
{
RCLCPP_INFO(get_logger(), "constructing %lu", hrt_absolute_time());
}
virtual ~ModuleBase() {}
/**
* @brief main Main entry point to the module that should be
* called directly from the module's main method.
* @param argc The task argument count.
* @param argc Pointer to the task argument variable array.
* @return Returns 0 iff successful, -1 otherwise.
*/
static int main(int argc, char *argv[])
{
return ret;
}
/**
* @brief Print the status if the module is running. This can be overridden by the module to provide
* more specific information.
* @return Returns 0 iff successful, -1 otherwise.
*/
virtual int print_status()
{
PX4_INFO("running");
return 0;
}
/**
* @brief Main loop method for modules running in their own thread. Called from run_trampoline().
* This method must return when should_exit() returns true.
*/
virtual void run()
{
}
/**
* @brief Returns the status of the module.
* @return Returns true if the module is running, false otherwise.
*/
static bool is_running()
{
return _task_id != -1;
}
protected:
/**
* @brief Tells the module to stop (used from outside or inside the module thread).
*/
virtual void request_stop()
{
_task_should_exit.store(true);
}
/**
* @brief Checks if the module should stop (used within the module thread).
* @return Returns True iff successful, false otherwise.
*/
bool should_exit() const
{
return _task_should_exit.load();
}
/**
* @brief Exits the module and delete the object. Called from within the module's thread.
* For work queue modules, this needs to be called from the derived class in the
* cycle method, when should_exit() returns true.
*/
static void exit_and_cleanup()
{
// Take the lock here:
// - if startup fails and we're faster than the parent thread, it will set
// _task_id and subsequently it will look like the task is running.
// - deleting the object must take place inside the lock.
lock_module();
delete _object.load();
_object.store(nullptr);
_task_id = -1; // Signal a potentially waiting thread for the module to exit that it can continue.
unlock_module();
}
/**
* @brief Waits until _object is initialized, (from the new thread). This can be called from task_spawn().
* @return Returns 0 iff successful, -1 on timeout or otherwise.
*/
static int wait_until_running(int timeout_ms = 1000)
{
int i = 0;
do {
px4_usleep(2000);
} while (!_object.load() && ++i < timeout_ms / 2);
if (i >= timeout_ms / 2) {
PX4_ERR("Timed out while waiting for thread to start");
return -1;
}
return 0;
}
/**
* @brief Get the module's object instance, (this is null if it's not running).
*/
static T *get_instance()
{
return (T *)_object.load();
}
/**
* @var _object Instance if the module is running.
* @note There will be one instance for each template type.
*/
static px4::atomic<T *> _object;
/** @var _task_id The task handle: -1 = invalid, otherwise task is assumed to be running. */
static int _task_id;
/** @var task_id_is_work_queue Value to indicate if the task runs on the work queue. */
static constexpr const int task_id_is_work_queue = -2;
private:
/**
* @brief lock_module Mutex to lock the module thread.
*/
static void lock_module()
{
pthread_mutex_lock(&px4_modules_mutex);
}
/**
* @brief unlock_module Mutex to unlock the module thread.
*/
static void unlock_module()
{
pthread_mutex_unlock(&px4_modules_mutex);
}
/** @var _task_should_exit Boolean flag to indicate if the task should exit. */
px4::atomic_bool _task_should_exit{false};
};
template<class T>
px4::atomic<T *> ModuleBase<T>::_object{nullptr};
template<class T>
int ModuleBase<T>::_task_id = -1;
#endif /* __cplusplus */
__BEGIN_DECLS
/**
* @brief Module documentation and command usage help methods.
* These are extracted with the Tools/px_process_module_doc.py
* script and must be kept in sync.
*/
#ifdef __PX4_NUTTX
/**
* @note Disable module description on NuttX to reduce Flash usage.
* There's a GCC bug (https://gcc.gnu.org/bugzilla/show_bug.cgi?id=55971), preventing us to use
* a macro, but GCC will remove the string as well with this empty inline method.
* @param description The provided functionality of the module and potentially the most important parameters.
*/
static inline void PRINT_MODULE_DESCRIPTION(const char *description) {}
#else
/**
* @brief Prints module documentation (will also be used for online documentation). It uses Markdown syntax
* and should include these sections:
* - ### Description
* Provided functionality of the module and potentially the most important parameters.
* - ### Implementation
* High-level implementation overview
* - ### Examples
* Examples how to use the CLI interface (if it's non-trivial)
*
* In addition to the Markdown syntax, a line beginning with '$ ' can be used to mark a command:
* $ module start -p param
*/
__EXPORT void PRINT_MODULE_DESCRIPTION(const char *description);
#endif
/**
* @brief Prints the command name.
* @param executable_name: command name used in scripts & CLI
* @param category one of: driver, estimator, controller, system, communication, command, template
*/
__EXPORT void PRINT_MODULE_USAGE_NAME(const char *executable_name, const char *category);
/**
* @brief Specify a subcategory (optional).
* @param subcategory e.g. if the category is 'driver', subcategory can be 'distance_sensor'
*/
__EXPORT void PRINT_MODULE_USAGE_SUBCATEGORY(const char *subcategory);
/**
* @brief Prints the name for a command without any sub-commands (@see PRINT_MODULE_USAGE_NAME()).
*/
__EXPORT void PRINT_MODULE_USAGE_NAME_SIMPLE(const char *executable_name, const char *category);
/**
* @brief Prints a command with a short description what it does.
*/
__EXPORT void PRINT_MODULE_USAGE_COMMAND_DESCR(const char *name, const char *description);
#define PRINT_MODULE_USAGE_COMMAND(name) \
PRINT_MODULE_USAGE_COMMAND_DESCR(name, NULL);
/**
* @brief Prints the default commands: stop & status.
*/
#define PRINT_MODULE_USAGE_DEFAULT_COMMANDS() \
PRINT_MODULE_USAGE_COMMAND("stop"); \
PRINT_MODULE_USAGE_COMMAND_DESCR("status", "print status info");
/**
* Print default params for I2C or SPI drivers
* @param i2c_support true if the driver supports I2C
* @param spi_support true if the driver supports SPI
*/
__EXPORT void PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(bool i2c_support, bool spi_support);
/**
* Configurable I2C address (via -a <address>)
*/
__EXPORT void PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(uint8_t default_address);
/**
* -k flag
*/
__EXPORT void PRINT_MODULE_USAGE_PARAMS_I2C_KEEP_RUNNING_FLAG(void);
/** @note Each of the PRINT_MODULE_USAGE_PARAM_* methods apply to the previous PRINT_MODULE_USAGE_COMMAND_DESCR(). */
/**
* @brief Prints an integer parameter.
* @param option_char The option character.
* @param default_val The parameter default value (set to -1 if not applicable).
* @param min_val The parameter minimum value.
* @param max_val The parameter value.
* @param description Pointer to the usage description.
* @param is_optional true if this parameter is optional
*/
__EXPORT void PRINT_MODULE_USAGE_PARAM_INT(char option_char, int default_val, int min_val, int max_val,
const char *description, bool is_optional);
/**
* @brief Prints a float parameter.
* @note See PRINT_MODULE_USAGE_PARAM_INT().
* @param default_val The parameter default value (set to NaN if not applicable).
* @param min_val The parameter minimum value.
* @param max_val The parameter maximum value.
* @param description Pointer to the usage description. Pointer to the usage description.
* @param is_optional true if this parameter is optional
*/
__EXPORT void PRINT_MODULE_USAGE_PARAM_FLOAT(char option_char, float default_val, float min_val, float max_val,
const char *description, bool is_optional);
/**
* @brief Prints a flag parameter, without any value.
* @note See PRINT_MODULE_USAGE_PARAM_INT().
* @param option_char The option character.
* @param description Pointer to the usage description.
* @param is_optional true if this parameter is optional
*/
__EXPORT void PRINT_MODULE_USAGE_PARAM_FLAG(char option_char, const char *description, bool is_optional);
/**
* @brief Prints a string parameter.
* @param option_char The option character.
* @param default_val The default value, can be nullptr.
* @param values The valid values, it has one of the following forms:
* - nullptr: leave unspecified, or any value is valid
* - "<file>" or "<file:dev>": a file or more specifically a device file (eg. serial device)
* - "<topic_name>": uORB topic name
* - "<value1> [<value2>]": a list of values
* - "on|off": a concrete set of valid strings separated by "|".
* @param description Pointer to the usage description.
* @param is_optional True iff this parameter is optional.
*/
__EXPORT void PRINT_MODULE_USAGE_PARAM_STRING(char option_char, const char *default_val, const char *values,
const char *description, bool is_optional);
/**
* @brief Prints a comment, that applies to the next arguments or parameters. For example to indicate that
* a parameter applies to several or all commands.
* @param comment
*/
__EXPORT void PRINT_MODULE_USAGE_PARAM_COMMENT(const char *comment);
/**
* @brief Prints the definition for an argument, which does not have the typical -p <val> form,
* but for example 'param set <param> <value>'
* @param values eg. "<file>", "<param> <value>" or "<value1> [<value2>]"
* @param description Pointer to the usage description.
* @param is_optional true if this parameter is optional
*/
__EXPORT void PRINT_MODULE_USAGE_ARG(const char *values, const char *description, bool is_optional);
__END_DECLS

View File

@ -0,0 +1,96 @@
/****************************************************************************
*
* Copyright (c) 2018 PX4 Development Team. 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 px4_module_params.h
*
* @class ModuleParams is a C++ base class for modules/classes using configuration parameters.
*/
#pragma once
#include <containers/List.hpp>
#include "param.h"
class ModuleParams : public ListNode<ModuleParams *>
{
public:
ModuleParams(ModuleParams *parent)
{
setParent(parent);
}
/**
* @brief Sets the parent module. This is typically not required,
* only in cases where the parent cannot be set via constructor.
*/
void setParent(ModuleParams *parent)
{
if (parent) {
parent->_children.add(this);
}
}
virtual ~ModuleParams() = default;
// Disallow copy construction and move assignment.
ModuleParams(const ModuleParams &) = delete;
ModuleParams &operator=(const ModuleParams &) = delete;
ModuleParams(ModuleParams &&) = delete;
ModuleParams &operator=(ModuleParams &&) = delete;
protected:
/**
* @brief Call this method whenever the module gets a parameter change notification.
* It will automatically call updateParams() for all children, which then call updateParamsImpl().
*/
virtual void updateParams()
{
for (const auto &child : _children) {
child->updateParams();
}
updateParamsImpl();
}
/**
* @brief The implementation for this is generated with the macro DEFINE_PARAMETERS()
*/
virtual void updateParamsImpl() {}
private:
/** @list _children The module parameter list of inheriting classes. */
List<ModuleParams *> _children;
};

View File

@ -0,0 +1,452 @@
/****************************************************************************
*
* Copyright (c) 2018 PX4 Development Team. 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 param.h
*
* C++ Parameter class
*/
#pragma once
#include "param_macros.h"
#include <float.h>
#include <math.h>
#include <parameters/px4_parameters.hpp>
#define _DEFINE_SINGLE_PARAMETER(x) \
do_not_explicitly_use_this_namespace::PAIR(x);
#define _CALL_UPDATE(x) \
STRIP(x).update();
// define the parameter update method, which will update all parameters.
// It is marked as 'final', so that wrong usages lead to a compile error (see below)
#define _DEFINE_PARAMETER_UPDATE_METHOD(...) \
protected: \
void updateParamsImpl() final { \
APPLY_ALL(_CALL_UPDATE, __VA_ARGS__) \
} \
private:
// Define a list of parameters. This macro also creates code to update parameters.
// If you get a compile error like:
// error: virtual function virtual void <class>::updateParamsImpl()
// It means you have a custom inheritance tree (at least one class with params that inherits from another
// class with params) and you need to use DEFINE_PARAMETERS_CUSTOM_PARENT() for **all** classes in
// that tree.
#define DEFINE_PARAMETERS(...) \
APPLY_ALL(_DEFINE_SINGLE_PARAMETER, __VA_ARGS__) \
_DEFINE_PARAMETER_UPDATE_METHOD(__VA_ARGS__)
#define _DEFINE_PARAMETER_UPDATE_METHOD_CUSTOM_PARENT(parent_class, ...) \
protected: \
void updateParamsImpl() override { \
parent_class::updateParamsImpl(); \
APPLY_ALL(_CALL_UPDATE, __VA_ARGS__) \
} \
private:
#define DEFINE_PARAMETERS_CUSTOM_PARENT(parent_class, ...) \
APPLY_ALL(_DEFINE_SINGLE_PARAMETER, __VA_ARGS__) \
_DEFINE_PARAMETER_UPDATE_METHOD_CUSTOM_PARENT(parent_class, __VA_ARGS__)
// This namespace never needs to be used directly. Use the DEFINE_PARAMETERS_CUSTOM_PARENT and
// DEFINE_PARAMETERS macros instead (the Param classes don't depend on using the macro, the macro just
// makes sure that update() is automatically called).
namespace do_not_explicitly_use_this_namespace
{
template<typename T, px4::params p>
class Param
{
};
// We use partial template specialization for each param type. This is only supported for classes, not individual methods,
// which is why we have to repeat the whole class
template<px4::params p>
class Param<float, p>
{
public:
// static type-check
static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_FLOAT, "parameter type must be float");
Param()
{
//param_set_used(handle());
update();
}
float get() const { return _val; }
const float &reference() const { return _val; }
/// Store the parameter value to the parameter storage (@see param_set())
bool commit() const
{
return true; // TODO
//return param_set(handle(), &_val) == 0;
}
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const
{
return true; // TODO
//return param_set_no_notification(handle(), &_val) == 0;
}
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(float val)
{
if (fabsf(val - _val) > FLT_EPSILON) {
set(val);
commit_no_notification();
return true;
}
return false;
}
void set(float val) { _val = val; }
void reset()
{
//param_reset_no_notification(handle()); // TODO
update();
}
bool update()
{
return true; // TODO
//return param_get(handle(), &_val) == 0;
}
//param_t handle() const { return param_handle(p); }
private:
float _val;
};
// external version
template<px4::params p>
class Param<float &, p>
{
public:
// static type-check
static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_FLOAT, "parameter type must be float");
Param(float &external_val)
: _val(external_val)
{
//param_set_used(handle()); // TODO
update();
}
float get() const { return _val; }
const float &reference() const { return _val; }
/// Store the parameter value to the parameter storage (@see param_set())
bool commit() const
{
//return param_set(handle(), &_val) == 0; // TODO
return true;
}
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const
{
return true;
//return param_set_no_notification(handle(), &_val) == 0;
}
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(float val)
{
if (fabsf(val - _val) > FLT_EPSILON) {
set(val);
commit_no_notification();
return true;
}
return false;
}
void set(float val) { _val = val; }
void reset()
{
//param_reset_no_notification(handle());
update();
}
bool update()
{
return true;
//return param_get(handle(), &_val) == 0;
}
//param_t handle() const { return param_handle(p); }
private:
float &_val;
};
template<px4::params p>
class Param<int32_t, p>
{
public:
// static type-check
static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_INT32, "parameter type must be int32_t");
Param()
{
//param_set_used(handle());
update();
}
int32_t get() const { return _val; }
const int32_t &reference() const { return _val; }
/// Store the parameter value to the parameter storage (@see param_set())
bool commit() const
{
return true;
//return param_set(handle(), &_val) == 0;
}
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const
{
//return param_set_no_notification(handle(), &_val) == 0;
return true;
}
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(int32_t val)
{
if (val != _val) {
set(val);
commit_no_notification();
return true;
}
return false;
}
void set(int32_t val) { _val = val; }
void reset()
{
//param_reset_no_notification(handle());
update();
}
bool update()
{
//return param_get(handle(), &_val) == 0;
return true;
}
//param_t handle() const { return param_handle(p); }
private:
int32_t _val;
};
//external version
template<px4::params p>
class Param<int32_t &, p>
{
public:
// static type-check
static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_INT32, "parameter type must be int32_t");
Param(int32_t &external_val)
: _val(external_val)
{
//param_set_used(handle());
update();
}
int32_t get() const { return _val; }
const int32_t &reference() const { return _val; }
/// Store the parameter value to the parameter storage (@see param_set())
bool commit() const
{
return true;
//return param_set(handle(), &_val) == 0;
}
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const
{
return true;
//return param_set_no_notification(handle(), &_val) == 0;
}
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(int32_t val)
{
if (val != _val) {
set(val);
commit_no_notification();
return true;
}
return false;
}
void set(int32_t val) { _val = val; }
void reset()
{
//param_reset_no_notification(handle());
update();
}
bool update()
{
//return param_get(handle(), &_val) == 0;
return true;
}
//param_t handle() const { return param_handle(p); }
private:
int32_t &_val;
};
template<px4::params p>
class Param<bool, p>
{
public:
// static type-check
static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_INT32, "parameter type must be int32_t");
Param()
{
//param_set_used(handle());
update();
}
bool get() const { return _val; }
const bool &reference() const { return _val; }
/// Store the parameter value to the parameter storage (@see param_set())
bool commit() const
{
int32_t value_int = (int32_t)_val;
//return param_set(handle(), &value_int) == 0;
return true;
}
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const
{
int32_t value_int = (int32_t)_val;
//return param_set_no_notification(handle(), &value_int) == 0;
return true;
}
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(bool val)
{
if (val != _val) {
set(val);
commit_no_notification();
return true;
}
return false;
}
void set(bool val) { _val = val; }
void reset()
{
//param_reset_no_notification(handle());
update();
}
bool update()
{
int32_t value_int;
int ret = 0;//param_get(handle(), &value_int);
if (ret == 0) {
_val = value_int != 0;
return true;
}
return false;
}
//param_t handle() const { return param_handle(p); }
private:
bool _val;
};
template <px4::params p>
using ParamFloat = Param<float, p>;
template <px4::params p>
using ParamInt = Param<int32_t, p>;
template <px4::params p>
using ParamExtFloat = Param<float &, p>;
template <px4::params p>
using ParamExtInt = Param<int32_t &, p>;
template <px4::params p>
using ParamBool = Param<bool, p>;
} /* namespace do_not_explicitly_use_this_namespace */
// Raise an appropriate compile error if a Param class is used directly (just to simplify debugging)
template<px4::params p>
class ParamInt
{
static_assert((int)p &&false, "Do not use this class directly, use the DEFINE_PARAMETERS macro instead");
};
template<px4::params p>
class ParamFloat
{
static_assert((int)p &&false, "Do not use this class directly, use the DEFINE_PARAMETERS macro instead");
};

View File

@ -0,0 +1,250 @@
/****************************************************************************
*
* Copyright (c) 2018 PX4 Development Team. 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 param_macros.h
*
* Helper macros used by px4_param.h
*/
#pragma once
#define APPLY0(t)
#define APPLY1(t, aaa) t(aaa)
#define APPLY2(t, aaa, aab) t(aaa) t(aab)
#define APPLY3(t, aaa, aab, aac) t(aaa) t(aab) t(aac)
#define APPLY4(t, aaa, aab, aac, aad) t(aaa) t(aab) t(aac) t(aad)
#define APPLY5(t, aaa, aab, aac, aad, aae) t(aaa) t(aab) t(aac) t(aad) t(aae)
#define APPLY6(t, aaa, aab, aac, aad, aae, aaf) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf)
#define APPLY7(t, aaa, aab, aac, aad, aae, aaf, aag) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag)
#define APPLY8(t, aaa, aab, aac, aad, aae, aaf, aag, aah) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah)
#define APPLY9(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai)
#define APPLY10(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj)
#define APPLY11(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak)
#define APPLY12(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal)
#define APPLY13(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam)
#define APPLY14(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan)
#define APPLY15(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao)
#define APPLY16(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap)
#define APPLY17(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq)
#define APPLY18(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar)
#define APPLY19(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas)
#define APPLY20(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat)
#define APPLY21(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau)
#define APPLY22(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav)
#define APPLY23(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw)
#define APPLY24(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax)
#define APPLY25(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay)
#define APPLY26(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz)
#define APPLY27(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba)
#define APPLY28(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb)
#define APPLY29(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc)
#define APPLY30(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd)
#define APPLY31(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe)
#define APPLY32(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf)
#define APPLY33(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg)
#define APPLY34(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh)
#define APPLY35(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi)
#define APPLY36(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj)
#define APPLY37(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk)
#define APPLY38(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl)
#define APPLY39(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm)
#define APPLY40(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn)
#define APPLY41(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo)
#define APPLY42(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp)
#define APPLY43(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq)
#define APPLY44(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr)
#define APPLY45(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs)
#define APPLY46(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt)
#define APPLY47(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu)
#define APPLY48(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv)
#define APPLY49(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw)
#define APPLY50(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx)
#define APPLY51(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby)
#define APPLY52(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz)
#define APPLY53(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca)
#define APPLY54(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb)
#define APPLY55(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc)
#define APPLY56(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd)
#define APPLY57(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace)
#define APPLY58(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf)
#define APPLY59(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg)
#define APPLY60(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach)
#define APPLY61(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci)
#define APPLY62(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj)
#define APPLY63(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack)
#define APPLY64(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl)
#define APPLY65(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm)
#define APPLY66(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn)
#define APPLY67(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco)
#define APPLY68(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp)
#define APPLY69(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq)
#define APPLY70(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr)
#define APPLY71(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs)
#define APPLY72(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act)
#define APPLY73(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu)
#define APPLY74(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv)
#define APPLY75(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw)
#define APPLY76(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx)
#define APPLY77(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy)
#define APPLY78(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz)
#define APPLY79(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada)
#define APPLY80(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb)
#define APPLY81(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc)
#define APPLY82(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add)
#define APPLY83(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade)
#define APPLY84(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf)
#define APPLY85(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg)
#define APPLY86(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh)
#define APPLY87(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi)
#define APPLY88(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj)
#define APPLY89(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk)
#define APPLY90(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl)
#define APPLY91(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm)
#define APPLY92(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn)
#define APPLY93(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado)
#define APPLY94(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp)
#define APPLY95(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq)
#define APPLY96(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr)
#define APPLY97(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads)
#define APPLY98(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt)
#define APPLY99(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu)
#define APPLY100(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv)
#define APPLY101(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw)
#define APPLY102(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx)
#define APPLY103(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady)
#define APPLY104(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz)
#define APPLY105(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea)
#define APPLY106(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb)
#define APPLY107(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec)
#define APPLY108(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed)
#define APPLY109(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee)
#define APPLY110(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef)
#define APPLY111(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg)
#define APPLY112(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh)
#define APPLY113(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei)
#define APPLY114(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej)
#define APPLY115(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek)
#define APPLY116(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael)
#define APPLY117(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem)
#define APPLY118(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen)
#define APPLY119(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo)
#define APPLY120(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep)
#define APPLY121(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq)
#define APPLY122(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer)
#define APPLY123(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes)
#define APPLY124(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet)
#define APPLY125(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu)
#define APPLY126(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev)
#define APPLY127(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew)
#define APPLY128(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex)
#define APPLY129(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey)
#define APPLY130(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez)
#define APPLY131(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa)
#define APPLY132(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb)
#define APPLY133(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc)
#define APPLY134(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd)
#define APPLY135(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd, afe) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd) t(afe)
#define APPLY136(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd, afe, aff) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd) t(afe) t(aff)
#define APPLY137(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd, afe, aff, afg) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd) t(afe) t(aff) t(afg)
#define APPLY138(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd, afe, aff, afg, afh) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd) t(afe) t(aff) t(afg) t(afh)
#define APPLY139(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd, afe, aff, afg, afh, afi) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd) t(afe) t(aff) t(afg) t(afh) t(afi)
#define APPLY140(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd, afe, aff, afg, afh, afi, afj) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd) t(afe) t(aff) t(afg) t(afh) t(afi) t(afj)
#define APPLY141(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd, afe, aff, afg, afh, afi, afj, afk) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd) t(afe) t(aff) t(afg) t(afh) t(afi) t(afj) t(afk)
#define APPLY142(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd, afe, aff, afg, afh, afi, afj, afk, afl) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd) t(afe) t(aff) t(afg) t(afh) t(afi) t(afj) t(afk) t(afl)
#define APPLY143(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd, afe, aff, afg, afh, afi, afj, afk, afl, afm) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd) t(afe) t(aff) t(afg) t(afh) t(afi) t(afj) t(afk) t(afl) t(afm)
#define APPLY144(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd, afe, aff, afg, afh, afi, afj, afk, afl, afm, afn) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd) t(afe) t(aff) t(afg) t(afh) t(afi) t(afj) t(afk) t(afl) t(afm) t(afn)
#define APPLY145(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd, afe, aff, afg, afh, afi, afj, afk, afl, afm, afn, afo) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd) t(afe) t(aff) t(afg) t(afh) t(afi) t(afj) t(afk) t(afl) t(afm) t(afn) t(afo)
#define APPLY146(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd, afe, aff, afg, afh, afi, afj, afk, afl, afm, afn, afo, afp) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd) t(afe) t(aff) t(afg) t(afh) t(afi) t(afj) t(afk) t(afl) t(afm) t(afn) t(afo) t(afp)
#define APPLY147(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd, afe, aff, afg, afh, afi, afj, afk, afl, afm, afn, afo, afp, afq) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd) t(afe) t(aff) t(afg) t(afh) t(afi) t(afj) t(afk) t(afl) t(afm) t(afn) t(afo) t(afp) t(afq)
#define APPLY148(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd, afe, aff, afg, afh, afi, afj, afk, afl, afm, afn, afo, afp, afq, afr) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd) t(afe) t(aff) t(afg) t(afh) t(afi) t(afj) t(afk) t(afl) t(afm) t(afn) t(afo) t(afp) t(afq) t(afr)
#define APPLY149(t, aaa, aab, aac, aad, aae, aaf, aag, aah, aai, aaj, aak, aal, aam, aan, aao, aap, aaq, aar, aas, aat, aau, aav, aaw, aax, aay, aaz, aba, abb, abc, abd, abe, abf, abg, abh, abi, abj, abk, abl, abm, abn, abo, abp, abq, abr, abs, abt, abu, abv, abw, abx, aby, abz, aca, acb, acc, acd, ace, acf, acg, ach, aci, acj, ack, acl, acm, acn, aco, acp, acq, acr, acs, act, acu, acv, acw, acx, acy, acz, ada, adb, adc, add, ade, adf, adg, adh, adi, adj, adk, adl, adm, adn, ado, adp, adq, adr, ads, adt, adu, adv, adw, adx, ady, adz, aea, aeb, aec, aed, aee, aef, aeg, aeh, aei, aej, aek, ael, aem, aen, aeo, aep, aeq, aer, aes, aet, aeu, aev, aew, aex, aey, aez, afa, afb, afc, afd, afe, aff, afg, afh, afi, afj, afk, afl, afm, afn, afo, afp, afq, afr, afs) t(aaa) t(aab) t(aac) t(aad) t(aae) t(aaf) t(aag) t(aah) t(aai) t(aaj) t(aak) t(aal) t(aam) t(aan) t(aao) t(aap) t(aaq) t(aar) t(aas) t(aat) t(aau) t(aav) t(aaw) t(aax) t(aay) t(aaz) t(aba) t(abb) t(abc) t(abd) t(abe) t(abf) t(abg) t(abh) t(abi) t(abj) t(abk) t(abl) t(abm) t(abn) t(abo) t(abp) t(abq) t(abr) t(abs) t(abt) t(abu) t(abv) t(abw) t(abx) t(aby) t(abz) t(aca) t(acb) t(acc) t(acd) t(ace) t(acf) t(acg) t(ach) t(aci) t(acj) t(ack) t(acl) t(acm) t(acn) t(aco) t(acp) t(acq) t(acr) t(acs) t(act) t(acu) t(acv) t(acw) t(acx) t(acy) t(acz) t(ada) t(adb) t(adc) t(add) t(ade) t(adf) t(adg) t(adh) t(adi) t(adj) t(adk) t(adl) t(adm) t(adn) t(ado) t(adp) t(adq) t(adr) t(ads) t(adt) t(adu) t(adv) t(adw) t(adx) t(ady) t(adz) t(aea) t(aeb) t(aec) t(aed) t(aee) t(aef) t(aeg) t(aeh) t(aei) t(aej) t(aek) t(ael) t(aem) t(aen) t(aeo) t(aep) t(aeq) t(aer) t(aes) t(aet) t(aeu) t(aev) t(aew) t(aex) t(aey) t(aez) t(afa) t(afb) t(afc) t(afd) t(afe) t(aff) t(afg) t(afh) t(afi) t(afj) t(afk) t(afl) t(afm) t(afn) t(afo) t(afp) t(afq) t(afr) t(afs)
#define NUM_ARGS_H1(dummy, x149, x148, x147, x146, x145, x144, x143, x142, x141, x140, x139, x138, x137, x136, x135, x134, x133, x132, x131, x130, x129, x128, x127, x126, x125, x124, x123, x122, x121, x120, x119, x118, x117, x116, x115, x114, x113, x112, x111, x110, x109, x108, x107, x106, x105, x104, x103, x102, x101, x100, x99, x98, x97, x96, x95, x94, x93, x92, x91, x90, x89, x88, x87, x86, x85, x84, x83, x82, x81, x80, x79, x78, x77, x76, x75, x74, x73, x72, x71, x70, x69, x68, x67, x66, x65, x64, x63, x62, x61, x60, x59, x58, x57, x56, x55, x54, x53, x52, x51, x50, x49, x48, x47, x46, x45, x44, x43, x42, x41, x40, x39, x38, x37, x36, x35, x34, x33, x32, x31, x30, x29, x28, x27, x26, x25, x24, x23, x22, x21, x20, x19, x18, x17, x16, x15, x14, x13, x12, x11, x10, x9, x8, x7, x6, x5, x4, x3, x2, x1, x0, ...) x0
#define NUM_ARGS(...) NUM_ARGS_H1(dummy, ##__VA_ARGS__, 149, 148, 147, 146, 145, 144, 143, 142, 141, 140, 139, 138, 137, 136, 135, 134, 133, 132, 131, 130, 129, 128, 127, 126, 125, 124, 123, 122, 121, 120, 119, 118, 117, 116, 115, 114, 113, 112, 111, 110, 109, 108, 107, 106, 105, 104, 103, 102, 101, 100, 99, 98, 97, 96, 95, 94, 93, 92, 91, 90, 89, 88, 87, 86, 85, 84, 83, 82, 81, 80, 79, 78, 77, 76, 75, 74, 73, 72, 71, 70, 69, 68, 67, 66, 65, 64, 63, 62, 61, 60, 59, 58, 57, 56, 55, 54, 53, 52, 51, 50, 49, 48, 47, 46, 45, 44, 43, 42, 41, 40, 39, 38, 37, 36, 35, 34, 33, 32, 31, 30, 29, 28, 27, 26, 25, 24, 23, 22, 21, 20, 19, 18, 17, 16, 15, 14, 13, 12, 11, 10, 9, 8, 7, 6, 5, 4, 3, 2, 1, 0)
#define APPLY_ALL_H3(t, n, ...) APPLY##n(t, __VA_ARGS__)
#define APPLY_ALL_H2(t, n, ...) APPLY_ALL_H3(t, n, __VA_ARGS__)
#define APPLY_ALL(t, ...) APPLY_ALL_H2(t, NUM_ARGS(__VA_ARGS__), __VA_ARGS__)
/*
* The above macros are auto-generated using the following python script:
#! /bin/python
# generate a C/C++ macro APPLY_ALL up to 'count' arguments
import sys
count = 150
def output(s):
sys.stdout.write(s)
def var_name(i):
""" get a variable name in the form abc from a counter i """
b = ord('a')
return chr(b+((i/26/26) % 26)) + chr(b+((i/26) % 26)) + chr(b+(i % 26))
for i in range(count):
output("#define APPLY{:}(t".format(i))
output(''.join([", {:}".format(var_name(j)) for j in range(i)]))
output(") ")
output(''.join(["t({:}) ".format(var_name(j)) for j in range(i)]))
output("\n")
output('''\n#define NUM_ARGS_H1(dummy{:}, ...) x0
'''.format(''.join([', x'+str(x) for x in reversed(range(count))])))
output('''#define NUM_ARGS(...) NUM_ARGS_H1(dummy, ##__VA_ARGS__{:})
'''.format(''.join([', '+str(x) for x in reversed(range(count))])))
output('''
#define APPLY_ALL_H3(t, n, ...) APPLY##n(t, __VA_ARGS__)
#define APPLY_ALL_H2(t, n, ...) APPLY_ALL_H3(t, n, __VA_ARGS__)
#define APPLY_ALL(t, ...) APPLY_ALL_H2(t, NUM_ARGS(__VA_ARGS__), __VA_ARGS__)
''')
*/
// helper macros to handle macro arguments in the form: (type) name
#define REM(...) __VA_ARGS__
#define EAT(...)
// Retrieve the type
#define TYPEOF(x) DETAIL_TYPEOF(DETAIL_TYPEOF_PROBE x,)
#define DETAIL_TYPEOF(...) DETAIL_TYPEOF_HEAD(__VA_ARGS__)
#define DETAIL_TYPEOF_HEAD(x, ...) REM x
#define DETAIL_TYPEOF_PROBE(...) (__VA_ARGS__),
// Strip off the type, get the name
#define STRIP(x) EAT x
// Show the type without parenthesis
#define PAIR(x) REM x

View File

@ -0,0 +1,40 @@
/****************************************************************************
*
* Copyright (c) 2015 Mark Charlebois. 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 px4_posix.h
*
* Includes POSIX-like functions for virtual character devices
*/
#pragma once

View File

@ -0,0 +1,40 @@
/****************************************************************************
*
* Copyright (C) 2015 Mark Charlebois. 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 px4_config.h
Configuration flags used in code.
*/
#pragma once

View File

@ -0,0 +1,108 @@
/****************************************************************************
*
* Copyright (c) 2016 PX4 Development Team. 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 sem.h
*
* Synchronization primitive: Semaphore
*/
#pragma once
#include <semaphore.h>
#if !defined(__PX4_NUTTX)
/* Values for protocol attribute */
#define SEM_PRIO_NONE 0
#define SEM_PRIO_INHERIT 1
#define SEM_PRIO_PROTECT 2
#define sem_setprotocol(s,p)
#endif
#if (defined(__PX4_DARWIN) || defined(__PX4_CYGWIN) || defined(__PX4_POSIX) || defined(__PX4_ROS2)) && !defined(__PX4_QURT)
__BEGIN_DECLS
typedef struct {
pthread_mutex_t lock;
pthread_cond_t wait;
int value;
} px4_sem_t;
__EXPORT int px4_sem_init(px4_sem_t *s, int pshared, unsigned value);
__EXPORT int px4_sem_setprotocol(px4_sem_t *s, int protocol);
__EXPORT int px4_sem_wait(px4_sem_t *s);
__EXPORT int px4_sem_trywait(px4_sem_t *sem);
__EXPORT int px4_sem_timedwait(px4_sem_t *sem, const struct timespec *abstime);
__EXPORT int px4_sem_post(px4_sem_t *s);
__EXPORT int px4_sem_getvalue(px4_sem_t *s, int *sval);
__EXPORT int px4_sem_destroy(px4_sem_t *s);
__END_DECLS
//#elif defined(__PX4_QURT)
//typedef sem_t px4_sem_t;
//#define px4_sem_init sem_init
//#define px4_sem_setprotocol sem_setprotocol
//#define px4_sem_wait sem_wait
//#define px4_sem_trywait sem_trywait
//#define px4_sem_post sem_post
//#define px4_sem_getvalue sem_getvalue
//#define px4_sem_destroy sem_destroy
#else
typedef sem_t px4_sem_t;
__BEGIN_DECLS
#define px4_sem_init sem_init
#define px4_sem_setprotocol sem_setprotocol
#define px4_sem_wait sem_wait
#define px4_sem_trywait sem_trywait
#define px4_sem_post sem_post
#define px4_sem_getvalue sem_getvalue
#define px4_sem_destroy sem_destroy
#if defined(__PX4_QURT)
__EXPORT int px4_sem_timedwait(px4_sem_t *sem, const struct timespec *abstime);
#else
#define px4_sem_timedwait sem_timedwait
#endif
__END_DECLS
#endif

View File

@ -0,0 +1,183 @@
/****************************************************************************
*
* Copyright (c) 2012-2017 PX4 Development Team. 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 px4_tasks.h
*
* @author Lorenz Meier <lorenz@px4.io>
* @author Mark Charlebois (2015) <charlebm@gmail.com>
*
* Preserve existing task API call signature with OS abstraction
*/
#pragma once
#include <stdbool.h>
#if defined(__PX4_NUTTX)
typedef int px4_task_t;
#include <sys/prctl.h>
#define px4_prctl prctl
/** Default scheduler type */
#if CONFIG_RR_INTERVAL > 0
# define SCHED_DEFAULT SCHED_RR
#else
# define SCHED_DEFAULT SCHED_FIFO
#endif
#define px4_task_exit(x) _exit(x)
#elif defined(__PX4_POSIX) || defined(__PX4_QURT)
#include <pthread.h>
#include <sched.h>
/** Default scheduler type */
#define SCHED_DEFAULT SCHED_FIFO
#if defined(__PX4_LINUX) || defined(__PX4_DARWIN) || defined(__PX4_CYGWIN) || defined(__PX4_ROS2)
#define SCHED_PRIORITY_MAX sched_get_priority_max(SCHED_FIFO)
#define SCHED_PRIORITY_MIN sched_get_priority_min(SCHED_FIFO)
#define SCHED_PRIORITY_DEFAULT (((sched_get_priority_max(SCHED_FIFO) - sched_get_priority_min(SCHED_FIFO)) / 2) + sched_get_priority_min(SCHED_FIFO))
#elif defined(__PX4_QURT)
#define SCHED_PRIORITY_MAX 255
#define SCHED_PRIORITY_MIN 0
#define SCHED_PRIORITY_DEFAULT 20
#else
#error "No target OS defined"
#endif
#if defined (__PX4_LINUX)
#include <sys/prctl.h>
#else
#define PR_SET_NAME 1
#endif
typedef int px4_task_t;
typedef struct {
int argc;
char **argv;
} px4_task_args_t;
#else
#error "No target OS defined"
#endif
// PX4 work queue starting high priority
#define PX4_WQ_HP_BASE (SCHED_PRIORITY_MAX - 15)
// Fast drivers - they need to run as quickly as possible to minimize control
// latency.
#define SCHED_PRIORITY_FAST_DRIVER (SCHED_PRIORITY_MAX - 0)
// Actuator outputs should run as soon as the rate controller publishes
// the actuator controls topic
#define SCHED_PRIORITY_ACTUATOR_OUTPUTS (PX4_WQ_HP_BASE - 3)
// Attitude controllers typically are in a blocking wait on driver data
// they should be the first to run on an update, using the current sensor
// data and the *previous* attitude reference from the position controller
// which typically runs at a slower rate
#define SCHED_PRIORITY_ATTITUDE_CONTROL (PX4_WQ_HP_BASE - 4)
// Estimators should run after the attitude controller but before anything
// else in the system. They wait on sensor data which is either coming
// from the sensor hub or from a driver. Keeping this class at a higher
// priority ensures that the estimator runs first if it can, but will
// wait for the sensor hub if its data is coming from it.
#define SCHED_PRIORITY_ESTIMATOR (PX4_WQ_HP_BASE - 5)
// Position controllers typically are in a blocking wait on estimator data
// so when new sensor data is available they will run last. Keeping them
// on a high priority ensures that they are the first process to be run
// when the estimator updates.
#define SCHED_PRIORITY_POSITION_CONTROL (PX4_WQ_HP_BASE - 7)
// The log capture (which stores log data into RAM) should run faster
// than other components, but should not run before the control pipeline
#define SCHED_PRIORITY_LOG_CAPTURE (PX4_WQ_HP_BASE - 10)
// Slow drivers should run at a rate where they do not impact the overall
// system execution
#define SCHED_PRIORITY_SLOW_DRIVER (PX4_WQ_HP_BASE - 35)
// The navigation system needs to execute regularly but has no realtime needs
#define SCHED_PRIORITY_NAVIGATION (SCHED_PRIORITY_DEFAULT + 5)
// SCHED_PRIORITY_DEFAULT
#define SCHED_PRIORITY_LOG_WRITER (SCHED_PRIORITY_DEFAULT - 10)
#define SCHED_PRIORITY_PARAMS (SCHED_PRIORITY_DEFAULT - 15)
// SCHED_PRIORITY_IDLE
typedef int (*px4_main_t)(int argc, char *argv[]);
__BEGIN_DECLS
/** Starts a task and performs any specific accounting, scheduler setup, etc. */
__EXPORT px4_task_t px4_task_spawn_cmd(const char *name,
int scheduler,
int priority,
int stack_size,
px4_main_t entry,
char *const argv[]);
/** Deletes a task - does not do resource cleanup **/
__EXPORT int px4_task_delete(px4_task_t pid);
/** Send a signal to a task **/
__EXPORT int px4_task_kill(px4_task_t pid, int sig);
/** Exit current task with return value **/
__EXPORT void px4_task_exit(int ret);
/** Show a list of running tasks **/
__EXPORT void px4_show_tasks(void);
/** See if a task is running **/
__EXPORT bool px4_task_is_running(const char *taskname);
#ifdef __PX4_POSIX
/** set process (and thread) options */
__EXPORT int px4_prctl(int option, const char *arg2, px4_task_t pid);
#endif
/** return the name of the current task */
__EXPORT const char *px4_get_taskname(void);
__END_DECLS

View File

@ -0,0 +1,6 @@
#define px4_clock_settime system_clock_settime
#define px4_usleep system_usleep
#define px4_sleep system_sleep
#define px4_pthread_cond_timedwait system_pthread_cond_timedwait

View File

@ -0,0 +1,140 @@
/****************************************************************************
* include/nuttx/wqueue.h
*
* Copyright (C) 2009, 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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.
*
****************************************************************************/
#pragma once
#if defined(__PX4_NUTTX)
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#elif defined(__PX4_POSIX)
#include <stdint.h>
#include <queue.h>
__BEGIN_DECLS
#define HPWORK 0
#define LPWORK 1
#define NWORKERS 2
struct wqueue_s {
pid_t pid; /* The task ID of the worker thread */
struct dq_queue_s q; /* The queue of pending work */
};
extern struct wqueue_s g_work[NWORKERS];
/* Defines the work callback */
typedef void (*worker_t)(void *arg);
struct work_s {
struct dq_entry_s dq; /* Implements a doubly linked list */
worker_t worker; /* Work callback */
void *arg; /* Callback argument */
uint64_t qtime; /* Time work queued */
uint32_t delay; /* Delay until work performed */
};
/****************************************************************************
* Name: work_queues_init()
*
* Description:
* Initialize the work queues.
*
****************************************************************************/
void work_queues_init(void);
/****************************************************************************
* Name: work_queue
*
* Description:
* Queue work to be performed at a later time. All queued work will be
* performed on the worker thread of of execution (not the caller's).
*
* The work structure is allocated by caller, but completely managed by
* the work queue logic. The caller should never modify the contents of
* the work queue structure; the caller should not call work_queue()
* again until either (1) the previous work has been performed and removed
* from the queue, or (2) work_cancel() has been called to cancel the work
* and remove it from the work queue.
*
* Input parameters:
* qid - The work queue ID
* work - The work structure to queue
* worker - The worker callback to be invoked. The callback will invoked
* on the worker thread of execution.
* arg - The argument that will be passed to the workder callback when
* int is invoked.
* delay - Delay (in clock ticks) from the time queue until the worker
* is invoked. Zero means to perform the work immediately.
*
* Returned Value:
* Zero on success, a negated errno on failure
*
****************************************************************************/
int work_queue(int qid, struct work_s *work, worker_t worker, void *arg, uint32_t delay);
/****************************************************************************
* Name: work_cancel
*
* Description:
* Cancel previously queued work. This removes work from the work queue.
* After work has been canceled, it may be re-queue by calling work_queue()
* again.
*
* Input parameters:
* qid - The work queue ID
* work - The previously queue work structure to cancel
*
* Returned Value:
* Zero on success, a negated errno on failure
*
****************************************************************************/
int work_cancel(int qid, struct work_s *work);
uint32_t clock_systimer(void);
int work_hpthread(int argc, char *argv[]);
int work_lpthread(int argc, char *argv[]);
__END_DECLS
#else
#error "Unknown target OS"
#endif

View File

@ -0,0 +1,134 @@
/************************************************************************
* include/queue.h
*
* Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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 __INCLUDE_QUEUE_H
#define __INCLUDE_QUEUE_H
/************************************************************************
* Included Files
************************************************************************/
#include <sys/types.h>
#ifdef __cplusplus
#include <cstddef> // NULL
#else
#include <stddef.h> // NULL
#endif
/************************************************************************
* Pre-processor Definitions
************************************************************************/
#define sq_init(q) do { (q)->head = NULL; (q)->tail = NULL; } while (0)
#define dq_init(q) do { (q)->head = NULL; (q)->tail = NULL; } while (0)
#define sq_next(p) ((p)->flink)
#define dq_next(p) ((p)->flink)
#define dq_prev(p) ((p)->blink)
#define sq_empty(q) ((q)->head == NULL)
#define dq_empty(q) ((q)->head == NULL)
#define sq_peek(q) ((q)->head)
#define dq_peek(q) ((q)->head)
// Required for Linux
#define FAR
/************************************************************************
* Global Type Declarations
************************************************************************/
struct sq_entry_s {
FAR struct sq_entry_s *flink;
};
typedef struct sq_entry_s sq_entry_t;
struct dq_entry_s {
FAR struct dq_entry_s *flink;
FAR struct dq_entry_s *blink;
};
typedef struct dq_entry_s dq_entry_t;
struct sq_queue_s {
FAR sq_entry_t *head;
FAR sq_entry_t *tail;
};
typedef struct sq_queue_s sq_queue_t;
struct dq_queue_s {
FAR dq_entry_t *head;
FAR dq_entry_t *tail;
};
typedef struct dq_queue_s dq_queue_t;
/************************************************************************
* Global Function Prototypes
************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C" {
#else
#define EXTERN extern
#endif
EXTERN void sq_addfirst(FAR sq_entry_t *node, sq_queue_t *queue);
EXTERN void dq_addfirst(FAR dq_entry_t *node, dq_queue_t *queue);
EXTERN void sq_addlast(FAR sq_entry_t *node, sq_queue_t *queue);
EXTERN void dq_addlast(FAR dq_entry_t *node, dq_queue_t *queue);
EXTERN void sq_addafter(FAR sq_entry_t *prev, FAR sq_entry_t *node,
sq_queue_t *queue);
EXTERN void dq_addafter(FAR dq_entry_t *prev, FAR dq_entry_t *node,
dq_queue_t *queue);
EXTERN void dq_addbefore(FAR dq_entry_t *next, FAR dq_entry_t *node,
dq_queue_t *queue);
EXTERN FAR sq_entry_t *sq_remafter(FAR sq_entry_t *node, sq_queue_t *queue);
EXTERN void sq_rem(FAR sq_entry_t *node, sq_queue_t *queue);
EXTERN void dq_rem(FAR dq_entry_t *node, dq_queue_t *queue);
EXTERN FAR sq_entry_t *sq_remlast(sq_queue_t *queue);
EXTERN FAR dq_entry_t *dq_remlast(dq_queue_t *queue);
EXTERN FAR sq_entry_t *sq_remfirst(sq_queue_t *queue);
EXTERN FAR dq_entry_t *dq_remfirst(dq_queue_t *queue);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* __INCLUDE_QUEUE_H_ */

View File

@ -0,0 +1,66 @@
/****************************************************************************
*
* Copyright (c) 2017 PX4 Development Team. 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 system_config.h
*
* Definitions used by all SITL and Linux targets
*/
#pragma once
#define PX4_CPU_UUID_BYTE_LENGTH 16
#define PX4_CPU_UUID_WORD32_LENGTH 4
#define PX4_CPU_MFGUID_BYTE_LENGTH PX4_CPU_UUID_BYTE_LENGTH
#define PX4_CPU_UUID_WORD32_UNIQUE_H 2 /* Most significant digits change the least */
#define PX4_CPU_UUID_WORD32_UNIQUE_M 1 /* Middle significant digits */
#define PX4_CPU_UUID_WORD32_UNIQUE_L 0 /* Least significant digits change the most */
#define PX4_CPU_UUID_WORD32_FORMAT_SIZE (PX4_CPU_UUID_WORD32_LENGTH-1+(2*PX4_CPU_UUID_BYTE_LENGTH)+1)
#define PX4_CPU_MFGUID_FORMAT_SIZE ((2*PX4_CPU_MFGUID_BYTE_LENGTH)+1)
#define BOARD_OVERRIDE_CPU_VERSION (-1)
#define board_mcu_version(rev, revstr, errata) BOARD_OVERRIDE_CPU_VERSION
#define BOARD_HAS_NO_UUID
#define CONFIG_NFILE_STREAMS 1
#define CONFIG_SCHED_WORKQUEUE 1
#define CONFIG_SCHED_HPWORK 1
#define CONFIG_SCHED_LPWORK 1
/** time in ms between checks for work in work queues **/
#define CONFIG_SCHED_WORKPERIOD 50000
#define CONFIG_SCHED_INSTRUMENTATION 1
#define CONFIG_MAX_TASKS 32

View File

@ -0,0 +1,148 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. 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 Publication.hpp
*
*/
#pragma once
#include "rclcpp/rclcpp.hpp"
#include "uORB.h"
namespace uORB
{
template <typename U> class DefaultQueueSize
{
private:
template <typename T>
static constexpr uint8_t get_queue_size(decltype(T::ORB_QUEUE_LENGTH) *)
{
return T::ORB_QUEUE_LENGTH;
}
template <typename T> static constexpr uint8_t get_queue_size(...)
{
return 1;
}
public:
static constexpr unsigned value = get_queue_size<U>(nullptr);
};
/**
* uORB publication wrapper class
*/
template<typename T, uint8_t ORB_QSIZE = DefaultQueueSize<T>::value>
class Publication
{
public:
/**
* Constructor
*
* @param meta The uORB metadata (usually from the ORB_ID() macro) for the topic.
*/
Publication(rclcpp::Node *node, ORB_ID id) : _node(*node), _id(id)
{
_publisher = _node.create_publisher<T>(::get_topic_string(_id), ORB_QSIZE); // TODO
}
bool advertised() { return (_publisher != nullptr); }
bool advertise()
{
if (!advertised()) {
_publisher = _node.create_publisher<T>(get_topic_string(_id), ORB_QSIZE);
}
return advertised();
}
/**
* Publish the struct
* @param data The uORB message struct we are updating.
*/
bool publish(const T &data)
{
if (!advertised()) {
advertise();
}
_publisher->publish(data);
return true;
}
private:
typename rclcpp::Publisher<T>::SharedPtr _publisher{nullptr};
rclcpp::Node &_node;
const ORB_ID _id;
};
/**
* The publication class with data embedded.
*/
template<typename T>
class PublicationData : public Publication<T>
{
public:
/**
* Constructor
*
* @param meta The uORB metadata (usually from the ORB_ID() macro) for the topic.
*/
PublicationData(ORB_ID id) : Publication<T>(id) {}
//PublicationData(const orb_metadata *meta) : Publication<T>(meta) {}
T &get() { return _data; }
void set(const T &data) { _data = data; }
// Publishes the embedded struct.
bool update() { return Publication<T>::publish(_data); }
bool update(const T &data)
{
_data = data;
return Publication<T>::publish(_data);
}
private:
T _data{};
};
} // namespace uORB

View File

@ -0,0 +1,167 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. 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 Subscription.hpp
*
*/
#pragma once
#include "rclcpp/rclcpp.hpp"
#include "uORB.h"
using std::placeholders::_1;
namespace uORB
{
class SubscriptionCallback;
template<typename S>
class Subscription2
{
public:
/**
* Constructor
*
* @param id The uORB ORB_ID enum for the topic.
* @param instance The instance for multi sub.
*/
Subscription2(rclcpp::Node *node, ORB_ID id, uint8_t instance = 0) :
_node(*node),
_id(id)
{
subscribe();
(void)instance; // TODO:
}
~Subscription2()
{
unsubscribe();
}
bool subscribe()
{
if (_subscription == nullptr) {
_subscription = _node.create_subscription<S>(::get_topic_string(_id), 1, std::bind(&Subscription2<S>::topic_callback,
this, _1));
}
return (_subscription != nullptr);
}
void unsubscribe() {}
bool valid() const { return _subscription != nullptr; }
bool advertised()
{
if (valid()) {
return true;
}
// try to initialize
if (subscribe()) {
// check again if valid
if (valid()) {
return true;
}
}
return false;
}
/**
* Check if there is a new update.
*/
//bool updated() { return advertised() && _node->updates_available(_last_generation); }
bool updated() { return true; }
/**
* Update the struct
* @param dst The uORB message struct we are updating.
*/
bool update(void *dst) { return updated() && copy(dst); }
/**
* Copy the struct
* @param dst The uORB message struct we are updating.
*/
bool copy(void *dst)
{
if (advertised()) {
S msg{};
//_subscription->return_message(&msg);
memcpy(dst, &msg, sizeof(S));
}
return false;
}
/**
* Change subscription instance
* @param instance The new multi-Subscription instance
*/
bool ChangeInstance(uint8_t instance);
uint8_t get_instance() const { return _instance; }
unsigned get_last_generation() const { return _last_generation; }
orb_id_t get_topic() const { return get_orb_meta(_id); }
protected:
typename rclcpp::Subscription<S>::SharedPtr _subscription{nullptr};
rclcpp::Node &_node;
unsigned _last_generation{0}; /**< last generation the subscriber has seen */
ORB_ID _id{ORB_ID::INVALID};
uint8_t _instance{0};
private:
void topic_callback(const typename S::SharedPtr msg)
{
(void)msg; // TODO
//_msg_buffer = msg;
_topic_generation++;
}
S _msg_buffer[1];
uint32_t _topic_generation{0};
};
} // namespace uORB

View File

@ -0,0 +1,155 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. 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 Subscription.hpp
*
*/
#pragma once
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/subscription_base.hpp"
#include "uORB.h"
namespace uORB
{
// Base subscription wrapper class
class SubscriptionBasic
{
public:
/**
* Constructor
*
* @param id The uORB ORB_ID enum for the topic.
* @param instance The instance for multi sub.
*/
Subscription(rclcpp::Node *node, ORB_ID id, uint8_t instance = 0) :
_node(*node),
_id(id)
{
subscribe();
(void)instance; // TODO:
}
~Subscription()
{
unsubscribe();
}
bool subscribe()
{
if (_subscription == nullptr) {
//_subscription = _node.create_subscription<px4::msg::VehicleStatus>("vehicle_status", 1, std::bind(&Subscription::topic_callback, this, _1));
}
return (_subscription != nullptr);
}
void unsubscribe() {}
bool valid() const { return _subscription != nullptr; }
bool advertised()
{
if (valid()) {
return true;
}
// try to initialize
if (subscribe()) {
// check again if valid
if (valid()) {
return true;
}
}
return false;
}
/**
* Check if there is a new update.
*/
//bool updated() { return advertised() && _node->updates_available(_last_generation); }
bool updated() { return true; }
/**
* Update the struct
* @param dst The uORB message struct we are updating.
*/
bool update(void *dst) { return updated() && copy(dst); }
/**
* Copy the struct
* @param dst The uORB message struct we are updating.
*/
bool copy(void *dst)
{
if (advertised()) {
//_subscription->return_message(&msg);
//memcpy(dst, &msg, sizeof(px4::msg::VehicleStatus));
}
return false;
}
/**
* Change subscription instance
* @param instance The new multi-Subscription instance
*/
bool ChangeInstance(uint8_t instance);
uint8_t get_instance() const { return _instance; }
unsigned get_last_generation() const { return _last_generation; }
orb_id_t get_topic() const { return get_orb_meta(_id); }
protected:
rclcpp::SubscriptionBase::SharedPtr _subscription{nullptr};
rclcpp::Node &_node;
unsigned _last_generation{0}; /**< last generation the subscriber has seen */
ORB_ID _id{ORB_ID::INVALID};
uint8_t _instance{0};
private:
uint32_t _topic_generation{0};
};
} // namespace uORB

View File

@ -0,0 +1,99 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. 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 <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
/**
* Object metadata.
*/
struct orb_metadata {
const char *o_name; /**< unique object name */
const uint16_t o_size; /**< object size */
const uint16_t o_size_no_padding; /**< object size w/o padding at the end (for logger) */
const char *o_fields; /**< semicolon separated list of fields (with type) */
uint8_t o_id; /**< ORB_ID enum */
};
typedef const struct orb_metadata *orb_id_t;
/**
* Maximum number of multi topic instances. This must be <= 10 (because it's the last char of the node path)
*/
#if defined(CONSTRAINED_MEMORY)
# define ORB_MULTI_MAX_INSTANCES 4
#else
# define ORB_MULTI_MAX_INSTANCES 10
#endif
#define ORB_ID(_name) &__orb_##_name
#if defined(__cplusplus)
# define ORB_DECLARE(_name) extern "C" const struct orb_metadata __orb_##_name __EXPORT
#else
# define ORB_DECLARE(_name) extern const struct orb_metadata __orb_##_name __EXPORT
#endif
#define ORB_DEFINE(_name, _struct, _size_no_padding, _fields, _orb_id_enum) \
const struct orb_metadata __orb_##_name = { \
#_name, \
sizeof(_struct), \
_size_no_padding, \
_fields, \
_orb_id_enum \
}; struct hack
/**
* Print a topic to console. Do not call this directly, use print_message() instead.
* @param meta orb topic metadata
* @param data expected to be aligned to the largest member
*/
void orb_print_message_internal(const struct orb_metadata *meta, const void *data, bool print_topic_name);
#ifndef PX4_INFO_RAW
# define PX4_INFO_RAW printf
#endif
#ifdef __cplusplus
#include <uORBTopics.hpp>
#endif // __cplusplus

View File

@ -0,0 +1,37 @@
############################################################################
#
# Copyright (c) 2021 PX4 Development Team. 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.
#
############################################################################
add_subdirectory(common)
add_subdirectory(${PX4_CHIP_MANUFACTURER})

View File

@ -0,0 +1,39 @@
############################################################################
#
# Copyright (c) 2015 PX4 Development Team. 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.
#
############################################################################
add_library(px4_layer STATIC
drv_hrt.cpp
px4_sem.cpp
)
target_compile_definitions(px4_layer PRIVATE MODULE_NAME="px4")
target_compile_options(px4_layer PRIVATE -Wno-cast-align) # TODO: fix and enable

View File

@ -0,0 +1,211 @@
/****************************************************************************
*
* Copyright (c) 2022 PX4 Development Team. 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 drv_hrt.cpp
*
* High-resolution timer with callouts and timekeeping.
*/
#include <drivers/drv_hrt.h>
#include <semaphore.h>
#include <time.h>
#include <string.h>
#include <errno.h>
#include <stdint.h>
#include <px4_platform_common/sem.h>
#include <queue.h>
sq_entry_t *sq_remafter(sq_entry_t *node, sq_queue_t *queue)
{
sq_entry_t *ret = node->flink;
if (queue->head && ret) {
if (queue->tail == ret) {
queue->tail = node;
node->flink = NULL;
} else {
node->flink = ret->flink;
}
ret->flink = NULL;
}
return ret;
}
void sq_rem(sq_entry_t *node, sq_queue_t *queue)
{
if (queue->head && node) {
if (node == queue->head) {
queue->head = node->flink;
if (node == queue->tail) {
queue->tail = NULL;
}
} else {
sq_entry_t *prev;
for (prev = (sq_entry_t *)queue->head;
prev && prev->flink != node;
prev = prev->flink) {}
if (prev) {
sq_remafter(prev, queue);
}
}
}
}
// Intervals in usec
static constexpr unsigned HRT_INTERVAL_MIN = 50;
static constexpr unsigned HRT_INTERVAL_MAX = 50000000;
/*
* Queue of callout entries.
*/
sq_entry_t callout_queue{};
/* latency baseline (last compare value applied) */
//static uint64_t latency_baseline;
/* latency histogram */
// const uint16_t latency_bucket_count = LATENCY_BUCKET_COUNT;
// const uint16_t latency_buckets[LATENCY_BUCKET_COUNT] = { 1, 2, 5, 10, 20, 50, 100, 1000 };
// __EXPORT uint32_t latency_counters[LATENCY_BUCKET_COUNT + 1];
static px4_sem_t _hrt_lock;
//static struct work_s _hrt_work;
static void hrt_lock()
{
px4_sem_wait(&_hrt_lock);
}
static void hrt_unlock()
{
px4_sem_post(&_hrt_lock);
}
/*
* Get absolute time.
*/
hrt_abstime hrt_absolute_time()
{
struct timespec ts;
clock_gettime(CLOCK_MONOTONIC, &ts);
return ts_to_abstime(&ts);
}
/*
* Store the absolute time in an interrupt-safe fashion.
*
* This function ensures that the timestamp cannot be seen half-written by an interrupt handler.
*/
void hrt_store_absolute_time(volatile hrt_abstime *t)
{
*t = hrt_absolute_time();
}
/*
* If this returns true, the entry has been invoked and removed from the callout list,
* or it has never been entered.
*
* Always returns false for repeating callouts.
*/
bool hrt_called(struct hrt_call *entry)
{
return (entry->deadline == 0);
}
/*
* Remove the entry from the callout list.
*/
void hrt_cancel(struct hrt_call *entry)
{
hrt_lock();
//sq_rem(&entry->link, &callout_queue);
entry->deadline = 0;
/* if this is a periodic call being removed by the callout, prevent it from
* being re-entered when the callout returns.
*/
entry->period = 0;
hrt_unlock();
// endif
}
/*
* initialise a hrt_call structure
*/
void hrt_call_init(struct hrt_call *entry)
{
memset(entry, 0, sizeof(*entry));
}
/*
* delay a hrt_call_every() periodic call by the given number of
* microseconds. This should be called from within the callout to
* cause the callout to be re-scheduled for a later time. The periodic
* callouts will then continue from that new base time at the
* previously specified period.
*/
void hrt_call_delay(struct hrt_call *entry, hrt_abstime delay)
{
entry->deadline = hrt_absolute_time() + delay;
}
/*
* Initialise the HRT.
*/
void hrt_init()
{
//sq_init(&callout_queue);
int sem_ret = px4_sem_init(&_hrt_lock, 0, 1);
if (sem_ret) {
//PX4_ERR("SEM INIT FAIL: %s", strerror(errno));
}
}
int px4_clock_gettime(clockid_t clk_id, struct timespec *tp)
{
return system_clock_gettime(clk_id, tp);
}

View File

@ -0,0 +1,51 @@
/****************************************************************************
*
* Copyright (c) 2019 PX4 Development Team. 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 <stdint.h>
#include <stdbool.h>
typedef int (*xcpt_t)(int irq, void *context, void *arg);
static inline int px4_arch_configgpio(uint32_t pinset) { return -1; }
static inline int px4_arch_unconfiggpio(uint32_t pinset) { return -1; }
static inline bool px4_arch_gpioread(uint32_t pinset) { return false; }
static inline void px4_arch_gpiowrite(uint32_t pinset, bool value) { }
static inline int px4_arch_gpiosetevent(uint32_t pinset, bool risingedge, bool fallingedge,
bool event, xcpt_t func, void *arg) { return -1; }
#define px4_udelay(usec) px4_usleep(usec)
#define px4_mdelay(msec) px4_msleep(msec)
#define px4_cache_aligned_data()
#define px4_cache_aligned_alloc malloc

View File

@ -0,0 +1,19 @@
// PX4 bridge
// serial/UDP/TCP
// all data in -> publish
// data in then publish rclcpp::Publish
// time sync
int main()
{
return 0;
}

View File

@ -0,0 +1,219 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. 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 px4_sem.cpp
*
* PX4 Middleware Wrapper Linux Implementation
*/
#include <px4_platform_common/defines.h>
#include <px4_platform_common/workqueue.h>
#include <px4_platform_common/sem.h>
#include <px4_platform_common/time.h>
#include <stdint.h>
#include <stdio.h>
#include <pthread.h>
#include <errno.h>
#if (defined(__PX4_DARWIN) || defined(__PX4_CYGWIN) || defined(__PX4_POSIX)) && !defined(__PX4_QURT)
#include <px4_platform_common/posix.h>
int px4_sem_init(px4_sem_t *s, int pshared, unsigned value)
{
// We do not used the process shared arg
(void)pshared;
s->value = value;
pthread_cond_init(&(s->wait), nullptr);
pthread_mutex_init(&(s->lock), nullptr);
#if !defined(__PX4_DARWIN)
// We want to use CLOCK_MONOTONIC if possible but we can't on macOS
// because it's not available.
pthread_condattr_t attr;
pthread_condattr_init(&attr);
pthread_condattr_setclock(&attr, CLOCK_MONOTONIC);
pthread_cond_init(&(s->wait), &attr);
#endif
return 0;
}
int px4_sem_setprotocol(px4_sem_t *s, int protocol)
{
return 0;
}
int px4_sem_wait(px4_sem_t *s)
{
int ret = pthread_mutex_lock(&(s->lock));
if (ret) {
return ret;
}
s->value--;
if (s->value < 0) {
ret = pthread_cond_wait(&(s->wait), &(s->lock));
} else {
ret = 0;
}
if (ret) {
//PX4_WARN("px4_sem_wait failure");
}
int mret = pthread_mutex_unlock(&(s->lock));
return (ret) ? ret : mret;
}
int px4_sem_trywait(px4_sem_t *s)
{
int ret = pthread_mutex_lock(&(s->lock));
if (ret) {
return ret;
}
if (s->value <= 0) {
errno = EAGAIN;
ret = -1;
} else {
s->value--;
}
int mret = pthread_mutex_unlock(&(s->lock));
return (ret) ? ret : mret;
}
int px4_sem_timedwait(px4_sem_t *s, const struct timespec *abstime)
{
int ret = pthread_mutex_lock(&(s->lock));
if (ret) {
return ret;
}
s->value--;
errno = 0;
if (s->value < 0) {
ret = px4_pthread_cond_timedwait(&(s->wait), &(s->lock), abstime);
} else {
ret = 0;
}
errno = ret;
if (ret != 0 && ret != ETIMEDOUT) {
setbuf(stdout, nullptr);
setbuf(stderr, nullptr);
const unsigned NAMELEN = 32;
char thread_name[NAMELEN] = {};
(void)pthread_getname_np(pthread_self(), thread_name, NAMELEN);
//PX4_WARN("%s: px4_sem_timedwait failure: ret: %d", thread_name, ret);
}
int mret = pthread_mutex_unlock(&(s->lock));
if (ret || mret) {
return -1;
}
return 0;
}
int px4_sem_post(px4_sem_t *s)
{
int ret = pthread_mutex_lock(&(s->lock));
if (ret) {
return ret;
}
s->value++;
if (s->value <= 0) {
ret = pthread_cond_signal(&(s->wait));
} else {
ret = 0;
}
if (ret) {
//PX4_WARN("px4_sem_post failure");
}
int mret = pthread_mutex_unlock(&(s->lock));
// return the cond signal failure if present,
// else return the mutex status
return (ret) ? ret : mret;
}
int px4_sem_getvalue(px4_sem_t *s, int *sval)
{
int ret = pthread_mutex_lock(&(s->lock));
if (ret) {
//PX4_WARN("px4_sem_getvalue failure");
}
if (ret) {
return ret;
}
*sval = s->value;
ret = pthread_mutex_unlock(&(s->lock));
return ret;
}
int px4_sem_destroy(px4_sem_t *s)
{
pthread_mutex_lock(&(s->lock));
pthread_cond_destroy(&(s->wait));
pthread_mutex_unlock(&(s->lock));
pthread_mutex_destroy(&(s->lock));
return 0;
}
#endif

View File

@ -0,0 +1,34 @@
############################################################################
#
# Copyright (c) 2019 PX4 Development Team. 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.
#
############################################################################
add_subdirectory(${PX4_CHIP})

View File

@ -0,0 +1,32 @@
############################################################################
#
# Copyright (c) 2021 PX4 Development Team. 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.
#
############################################################################

View File

@ -0,0 +1,53 @@
/****************************************************************************
*
* Copyright (C) 2020 PX4 Development Team. 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 <px4_platform_common/i2c.h>
static inline constexpr px4_i2c_bus_t initI2CBusInternal(int bus)
{
px4_i2c_bus_t ret{};
ret.bus = bus;
ret.is_external = false;
return ret;
}
static inline constexpr px4_i2c_bus_t initI2CBusExternal(int bus)
{
px4_i2c_bus_t ret{};
ret.bus = bus;
ret.is_external = true;
return ret;
}

View File

@ -0,0 +1,36 @@
/****************************************************************************
*
* Copyright (c) 2019 PX4 Development Team. 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 <px4_platform/micro_hal.h>

View File

@ -0,0 +1,59 @@
/****************************************************************************
*
* Copyright (C) 2020 PX4 Development Team. 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 <px4_platform_common/spi.h>
static inline constexpr px4_spi_bus_device_t initSPIDevice(uint8_t devid_driver, uint8_t cs_index)
{
px4_spi_bus_device_t ret{};
ret.cs_gpio = 1; // set to some non-zero value to indicate this is used
ret.devid = PX4_SPIDEV_ID(PX4_SPI_DEVICE_ID, cs_index);
ret.devtype_driver = devid_driver;
return ret;
}
static inline constexpr px4_spi_bus_t initSPIBus(int bus, const px4_spi_bus_devices_t &devices)
{
px4_spi_bus_t ret{};
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
ret.devices[i] = devices.devices[i];
}
ret.bus = bus;
ret.is_external = false; // all buses are marked internal on Linux
ret.requires_locking = false;
return ret;
}

View File

@ -39,7 +39,7 @@ add_dependencies(drivers_bootloaders prebuild_targets)
include_directories(include)
target_include_directories(drivers_bootloaders INTERFACE ${CMAKE_CURRENT_SOURCE_DIR})
target_link_libraries(drivers_bootloaders PRIVATE systemlib)
target_link_libraries(drivers_bootloaders PRIVATE crc)
# generate bootloader_app_shared_t
if(NOT "${PX4_BOARD_LABEL}" MATCHES "canbootloader")

View File

@ -45,7 +45,7 @@
#include "boot_alt_app_shared.h"
#include <lib/systemlib/crc.h>
#include <lib/crc/crc.h>
/****************************************************************************
* Name: bootloader_alt_app_shared_read

View File

@ -46,7 +46,7 @@
#include "arm_internal.h"
#include "boot_app_shared.h"
#include <lib/systemlib/crc.h>
#include <lib/crc/crc.h>
#define BOOTLOADER_COMMON_APP_SIGNATURE 0xB0A04150u
#define BOOTLOADER_COMMON_BOOTLOADER_SIGNATURE 0xB0A0424Cu

View File

@ -55,7 +55,6 @@
#include <perf/perf_counter.h>
#include <systemlib/err.h>
#include <systemlib/conversions.h>
#include <nuttx/arch.h>
#include <nuttx/clock.h>

View File

@ -31,44 +31,45 @@
#
############################################################################
add_subdirectory(adsb)
add_subdirectory(airspeed)
add_subdirectory(avoidance)
add_subdirectory(battery)
add_subdirectory(bezier)
add_subdirectory(button)
add_subdirectory(cdev)
add_subdirectory(circuit_breaker)
add_subdirectory(collision_prevention)
add_subdirectory(component_information)
add_subdirectory(controllib)
add_subdirectory(conversion)
add_subdirectory(crypto)
add_subdirectory(drivers)
add_subdirectory(field_sensor_bias_estimator)
add_subdirectory(geo)
add_subdirectory(hysteresis)
add_subdirectory(l1)
add_subdirectory(led)
add_subdirectory(matrix)
add_subdirectory(mathlib)
add_subdirectory(mixer_module)
add_subdirectory(motion_planning)
add_subdirectory(npfg)
add_subdirectory(perf)
add_subdirectory(pid)
add_subdirectory(pid_design)
add_subdirectory(rate_control)
add_subdirectory(rc)
add_subdirectory(sensor_calibration)
add_subdirectory(slew_rate)
add_subdirectory(systemlib)
add_subdirectory(system_identification)
add_subdirectory(tecs)
add_subdirectory(terrain_estimation)
add_subdirectory(timesync)
add_subdirectory(tunes)
add_subdirectory(version)
add_subdirectory(weather_vane)
add_subdirectory(wind_estimator)
add_subdirectory(world_magnetic_model)
add_subdirectory(adsb EXCLUDE_FROM_ALL)
add_subdirectory(airspeed EXCLUDE_FROM_ALL)
add_subdirectory(avoidance EXCLUDE_FROM_ALL)
add_subdirectory(battery EXCLUDE_FROM_ALL)
add_subdirectory(bezier EXCLUDE_FROM_ALL)
add_subdirectory(button EXCLUDE_FROM_ALL)
add_subdirectory(cdev EXCLUDE_FROM_ALL)
add_subdirectory(circuit_breaker EXCLUDE_FROM_ALL)
add_subdirectory(collision_prevention EXCLUDE_FROM_ALL)
add_subdirectory(component_information EXCLUDE_FROM_ALL)
add_subdirectory(controllib EXCLUDE_FROM_ALL)
add_subdirectory(conversion EXCLUDE_FROM_ALL)
add_subdirectory(crc EXCLUDE_FROM_ALL)
add_subdirectory(crypto EXCLUDE_FROM_ALL)
add_subdirectory(drivers EXCLUDE_FROM_ALL)
add_subdirectory(field_sensor_bias_estimator EXCLUDE_FROM_ALL)
add_subdirectory(geo EXCLUDE_FROM_ALL)
add_subdirectory(hysteresis EXCLUDE_FROM_ALL)
add_subdirectory(l1 EXCLUDE_FROM_ALL)
add_subdirectory(led EXCLUDE_FROM_ALL)
add_subdirectory(matrix EXCLUDE_FROM_ALL)
add_subdirectory(mathlib EXCLUDE_FROM_ALL)
add_subdirectory(mixer_module EXCLUDE_FROM_ALL)
add_subdirectory(motion_planning EXCLUDE_FROM_ALL)
add_subdirectory(npfg EXCLUDE_FROM_ALL)
add_subdirectory(perf EXCLUDE_FROM_ALL)
add_subdirectory(pid EXCLUDE_FROM_ALL)
add_subdirectory(pid_design EXCLUDE_FROM_ALL)
add_subdirectory(rate_control EXCLUDE_FROM_ALL)
add_subdirectory(rc EXCLUDE_FROM_ALL)
add_subdirectory(sensor_calibration EXCLUDE_FROM_ALL)
add_subdirectory(slew_rate EXCLUDE_FROM_ALL)
add_subdirectory(systemlib EXCLUDE_FROM_ALL)
add_subdirectory(system_identification EXCLUDE_FROM_ALL)
add_subdirectory(tecs EXCLUDE_FROM_ALL)
add_subdirectory(terrain_estimation EXCLUDE_FROM_ALL)
add_subdirectory(timesync EXCLUDE_FROM_ALL)
add_subdirectory(tunes EXCLUDE_FROM_ALL)
add_subdirectory(version EXCLUDE_FROM_ALL)
add_subdirectory(weather_vane EXCLUDE_FROM_ALL)
add_subdirectory(wind_estimator EXCLUDE_FROM_ALL)
add_subdirectory(world_magnetic_model EXCLUDE_FROM_ALL)

View File

@ -0,0 +1,39 @@
############################################################################
#
# Copyright (c) 2015-2022 PX4 Development Team. 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.
#
############################################################################
add_library(crc STATIC EXCLUDE_FROM_ALL
crc.c
crc.h
)
add_dependencies(crc prebuild_targets)
target_compile_options(crc PRIVATE ${MAX_CUSTOM_OPT_LEVEL})

View File

@ -172,8 +172,8 @@ if(${PX4_PLATFORM} STREQUAL "nuttx")
endif()
# TODO: find a better way to do this
if (NOT "${PX4_BOARD}" MATCHES "px4_io")
add_library(parameters
if(NOT "${PX4_BOARD}" MATCHES "px4_io")
add_library(parameters STATIC EXCLUDE_FROM_ALL
${SRCS}
px4_parameters.hpp
)
@ -188,7 +188,7 @@ if (NOT "${PX4_BOARD}" MATCHES "px4_io")
-Wno-sign-compare # TODO: fix and enable
)
else()
add_library(parameters ${PX4_SOURCE_DIR}/platforms/common/empty.c)
add_library(parameters STATIC EXCLUDE_FROM_ALL ${PX4_SOURCE_DIR}/platforms/common/empty.c)
endif()
add_dependencies(parameters prebuild_targets)

View File

@ -32,17 +32,17 @@
############################################################################
set(SRCS
conversions.c
conversions.h
crc.c
crc.h
err.h
mavlink_log.cpp
mavlink_log.h
px4_macros.h
)
if(${PX4_PLATFORM} STREQUAL "nuttx")
list(APPEND SRCS
otp.c
otp.h
ppm_decode.h
)
endif()

View File

@ -49,9 +49,8 @@
#include <math.h>
#include <unistd.h>
#include <string.h> // memset
#include "conversions.h"
#include "otp.h"
#include "err.h" // warnx
#include "err.h" // warnx
#include <assert.h>