diff --git a/.gitignore b/.gitignore index 687a93d87..659bbe51f 100644 --- a/.gitignore +++ b/.gitignore @@ -3,9 +3,14 @@ CMakeCache.txt *.cmake !clang-cxx-dev-tools.cmake !compilerSettings.cmake +!ct-cmake-helpers.cmake !FindIPOPT.cmake !Findblasfeo.cmake !Findhpipm.cmake +!FindCppAD.cmake +!FindCppADCG.cmake +!Findllvm.cmake +!Findclang.cmake !ct_core/cmake/ct_coreConfig.cmake !ct_optcon/cmake/ct_optconConfig.cmake !ct_rbd/cmake/ct_rbdConfig.cmake diff --git a/.travis.yml b/.travis.yml index 1b2df131d..bef98687f 100644 --- a/.travis.yml +++ b/.travis.yml @@ -5,9 +5,9 @@ cache: language: generic matrix: include: - - name: "Xenial kinetic" - dist: xenial - env: ROS_DISTRO=kinetic + - name: "Bionic melodic" + dist: bionic + env: ROS_DISTRO=melodic env: global: @@ -82,7 +82,7 @@ script: - cd ~/catkin_ws - catkin clean --all - catkin config --blacklist ct_doc - - catkin build -DBUILD_TESTS=true -DCMAKE_BUILD_TYPE=Release -DCMAKE_CXX_FLAGS="-w" + - catkin build -DUSE_CLANG=true -DBUILD_TESTS=true -DCMAKE_BUILD_TYPE=Release -DCMAKE_CXX_FLAGS="-w" # Run the tests, ensuring the path is set correctly. # we do not want to run the kindr tests - catkin config --blacklist kindr diff --git a/NOTICE.txt b/NOTICE.txt index 84a97c2dc..dacb9bebe 100644 --- a/NOTICE.txt +++ b/NOTICE.txt @@ -7,17 +7,11 @@ Copyright 2014-2018 ETH Zurich This software has been developed at the Agile & Dexterous Robotics Lab at ETH Zurich under the lead of Michael Neunert and Markus Giftthaler. -Software included in any folder named "external" and any subsequent -subfolders is software developed by third parties and not by the -authors above. Thererfore, neither the developers nor the institution -listed above holds copyright for this external software. Furthermore, -external software might be distributed under different licences -agreements included in the subfolders. Authors: -Michael Neunert, Markus Giftthaler, +Michael Neunert, Markus Stäuble, Diego Pardo, Farbod Farshidian, diff --git a/README.md b/README.md index 802dff4f0..992660a56 100644 --- a/README.md +++ b/README.md @@ -1,5 +1,5 @@ # Control Toolbox -![Travis (.org) branch](https://img.shields.io/travis/ethz-adrl/control-toolbox/3.0.1.svg?style=popout-square) +![Travis (.org) branch](https://img.shields.io/travis/ethz-adrl/control-toolbox/3.0.2.svg?style=popout-square) ![GitHub top language](https://img.shields.io/github/languages/top/ethz-adrl/control-toolbox.svg?style=social) ![GitHub](https://img.shields.io/github/license/ethz-adrl/control-toolbox.svg?style=social) diff --git a/ct/CMakeLists.txt b/ct/CMakeLists.txt index ee7785b4a..c5d811058 100644 --- a/ct/CMakeLists.txt +++ b/ct/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.3) -project(ct VERSION 3.0.1 LANGUAGES CXX) +project(ct VERSION 3.0.2 LANGUAGES CXX) #Make sure metapackage does not fail when building documentation add_custom_target(doc diff --git a/ct/cmake/ct-cmake-helpers.cmake b/ct/cmake/ct-cmake-helpers.cmake new file mode 100644 index 000000000..78a52b60a --- /dev/null +++ b/ct/cmake/ct-cmake-helpers.cmake @@ -0,0 +1,12 @@ + +# import interface compile definitions from ext_target as cmake option +function(importInterfaceCompileDefinitionsAsOptions ext_target) + + get_property(_if_compile_defs TARGET ${ext_target} PROPERTY INTERFACE_COMPILE_DEFINITIONS) + + foreach( i ${_if_compile_defs} ) + set(${i} ON PARENT_SCOPE) # mark all interface compile definitions as options + message(STATUS "Importing compile definition " ${i} " as option.") + endforeach() + +endfunction() \ No newline at end of file diff --git a/ct/install_cppadcg.sh b/ct/install_cppadcg.sh new file mode 100755 index 000000000..42eee6056 --- /dev/null +++ b/ct/install_cppadcg.sh @@ -0,0 +1,28 @@ +#!/bin/bash + +## get llvm +yes Y | sudo apt-get install llvm + +## get clang +# todo + +## install CppAD +mkdir /tmp/cppadcg_deps +cd /tmp/cppadcg_deps +wget https://github.com/coin-or/CppAD/archive/20190200.4.tar.gz +tar -xzf 20190200.4.tar.gz +cd CppAD-20190200.4 +mkdir build +cd build +cmake -Dcppad_prefix:PATH='/usr/local' .. +sudo make install + + +## install CppADCodeGen +git clone https://github.com/joaoleal/CppADCodeGen.git /tmp/CppADCodeGen +cd /tmp/CppADCodeGen +mkdir -p build +cd build +cmake .. #-DLLVM_VERSION=6.0 +make +sudo make install diff --git a/ct/install_deps.sh b/ct/install_deps.sh index bb2c10664..66a22eba6 100755 --- a/ct/install_deps.sh +++ b/ct/install_deps.sh @@ -3,16 +3,25 @@ sudo apt-get update ## get lapack -sudo apt-get install liblapack-dev +yes Y | sudo apt-get install liblapack-dev ## get eigen3 -sudo apt-get install libeigen3-dev +yes Y | sudo apt-get install libeigen3-dev ## get cmake -sudo apt-get install cmake +yes Y | sudo apt-get install cmake ## get IPOPT -sudo apt-get install coinor-libipopt-dev +yes Y | sudo apt-get install coinor-libipopt-dev ## get boost -sudo apt-get install libboost-all-dev +yes Y | sudo apt-get install libboost-all-dev + +## get open mp +yes Y | sudo apt install libomp-dev + +## get clang +yes Y | sudo apt install clang + +## get CppAD and CppADCodeGen +sudo ./install_cppadcg.sh \ No newline at end of file diff --git a/ct/install_hpipm.sh b/ct/install_hpipm.sh new file mode 100755 index 000000000..35876d34e --- /dev/null +++ b/ct/install_hpipm.sh @@ -0,0 +1,20 @@ +#!/bin/bash + +## get blasfeo 0.1.1 +echo "now installing blasfeo 0.1.1 ..." +cd /tmp +git clone https://github.com/giaf/blasfeo.git +cd /tmp/blasfeo +git checkout 0.1.1 # we currently are on this release +make static_library +sudo make install_static + +## get hpipm 0.1.1 +echo "now installing hpipm 0.1.1 ..." +cd /tmp +git clone https://github.com/giaf/hpipm.git +cd /tmp/hpipm +git checkout 806c845 +make static_library +make examples +sudo make install_static \ No newline at end of file diff --git a/ct/package.xml b/ct/package.xml index a1981efe6..5d73d2834 100644 --- a/ct/package.xml +++ b/ct/package.xml @@ -1,8 +1,8 @@ ct - 3.0.1 + 3.0.2 - ADRL Control Toolbox 3.0.1 + ADRL Control Toolbox 3.0.2 Markus Giftthaler BSD-2 diff --git a/ct_core/CMakeLists.txt b/ct_core/CMakeLists.txt index 066cabe02..796f5a254 100755 --- a/ct_core/CMakeLists.txt +++ b/ct_core/CMakeLists.txt @@ -5,7 +5,7 @@ include(${CMAKE_CURRENT_SOURCE_DIR}/../ct/cmake/explicitTemplateHelpers.cmake) include(${CMAKE_CURRENT_SOURCE_DIR}/../ct/cmake/clang-cxx-dev-tools.cmake) -project(ct_core VERSION 3.0.1 LANGUAGES CXX) +project(ct_core VERSION 3.0.2 LANGUAGES CXX) set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake) @@ -14,13 +14,44 @@ set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -pthread -std=c++14 -Wall set(CMAKE_EXPORT_COMPILE_COMMANDS TRUE) +set(ct_core_LIBS "") + ## find and include required dependencies find_package(Eigen3 REQUIRED) find_package(Boost COMPONENTS REQUIRED) -set(ct_core_LIBS "") - ## find and include optional dependencies +find_package(llvm QUIET) +find_package(clang QUIET) +if(LLVM_FOUND AND CLANG_FOUND) + message(STATUS "Found LLVM/CLANG version " ${LLVM_VERSION_MAJOR}.${LLVM_VERSION_MINOR}) + set (LLVM ON) + list(APPEND ct_core_COMPILE_DEFINITIONS LLVM_VERSION_MAJOR=${LLVM_VERSION_MAJOR}) + list(APPEND ct_core_COMPILE_DEFINITIONS LLVM_VERSION_MINOR=${LLVM_VERSION_MINOR}) + list(APPEND ct_core_LIBS ${CLANG_LIBS}) + list(APPEND ct_core_LIBS ${LLVM_MODULE_LIBS}) + list(APPEND ct_core_target_include_dirs ${LLVM_INCLUDE_DIRS}) + list(APPEND ct_core_target_include_dirs ${CLANG_INCLUDE_DIRS}) +else() + message(STATUS "Could not find LLVM/CLANG, LLVM-JIT will not be available") +endif() +find_package(CppAD QUIET) +if(CPPAD_FOUND) + set(CPPAD ON) + list(APPEND ct_core_COMPILE_DEFINITIONS CPPAD) + list(APPEND ct_core_target_include_dirs ${CPPAD_INCLUDE_DIRS}) +else() + message(STATUS "Could not find CppAD, auto-diff will not be available") +endif() +find_package(CppADCG QUIET) +if(CPPADCG_FOUND) + set(CPPADCG ON) + list(APPEND ct_core_COMPILE_DEFINITIONS CPPADCG) + list(APPEND ct_core_target_include_dirs ${CPPADCG_INCLUDE_DIRS}) +else() + message(STATUS "Could not find CppADCodeGen, derivative code generation will not be available") +endif() + find_package(Qwt QUIET) find_package(Qt4 QUIET) if(QWT_FOUND AND Qt4_FOUND) @@ -32,15 +63,14 @@ else() message(STATUS "COMPILING WITHOUT QWT") endif() -## find and include optional dependencies find_package(PythonLibs 2.7 QUIET) if (PYTHONLIBS_FOUND) - message(STATUS "Python found") - list(APPEND ct_plot_COMPILE_DEFINITIONS PLOTTING_ENABLED) + message(STATUS "Found python 2.7") + list(APPEND ct_core_COMPILE_DEFINITIONS PLOTTING_ENABLED) message(STATUS "Python library path ... " ${PYTHON_LIBRARY}) list(APPEND ct_core_LIBS ${PYTHON_LIBRARY}) else() - message(STATUS "Python not found") + message(STATUS "Python not found, plotting will not be available") endif() @@ -55,16 +85,12 @@ configure_file(${CMAKE_CURRENT_SOURCE_DIR}/include/ct/core/templateDir.h.in ${CM ################### ## define the directories to be included in all ct_core targets -set(ct_core_target_include_dirs - ${EIGEN3_INCLUDE_DIR} - ${PYTHON_INCLUDE_DIRS} - ${QWT_INCLUDE_DIR} - $ - $ - $ - $ - $ -) +list(APPEND ct_core_target_include_dirs ${EIGEN3_INCLUDE_DIR}) +list(APPEND ct_core_target_include_dirs ${PYTHON_INCLUDE_DIRS}) +list(APPEND ct_core_target_include_dirs ${QWT_INCLUDE_DIR}) +list(APPEND ct_core_target_include_dirs $) +list(APPEND ct_core_target_include_dirs $) +list(APPEND ct_core_target_include_dirs $) ## declare prespec libraries set(PRESPEC_LIB_NAMES "") @@ -88,11 +114,12 @@ endif() ## create ct_core libraries add_library(ct_plot SHARED src/core/plot/plot.cpp) target_include_directories(ct_plot PUBLIC ${ct_core_target_include_dirs}) -target_compile_definitions(ct_plot PUBLIC ${ct_plot_COMPILE_DEFINITIONS}) +target_compile_definitions(ct_plot PUBLIC ${ct_core_COMPILE_DEFINITIONS}) target_link_libraries(ct_plot ${ct_core_LIBS}) add_library(ct_core INTERFACE) target_include_directories(ct_core INTERFACE ${ct_core_target_include_dirs}) +target_compile_definitions(ct_core INTERFACE ${ct_core_COMPILE_DEFINITIONS}) target_link_libraries(ct_core INTERFACE ${ct_core_LIBS} ${PRESPEC_LIB_NAMES} @@ -135,7 +162,6 @@ include(GNUInstallDirs) ## copy the header files install(DIRECTORY include/ct/core DESTINATION include/ct) -install(DIRECTORY include/ct/external DESTINATION include/ct) install(DIRECTORY examples/include/ct/core DESTINATION include/ct) ## copy the cmake files required for find_package() diff --git a/ct_core/cmake/FindCppAD.cmake b/ct_core/cmake/FindCppAD.cmake new file mode 100644 index 000000000..7eed22dd0 --- /dev/null +++ b/ct_core/cmake/FindCppAD.cmake @@ -0,0 +1,63 @@ + +IF (CPPAD_INCLUDES AND CPPAD_LIBRARIES) + SET(CPPAD_FIND_QUIETLY TRUE) +ENDIF () + + +IF(DEFINED CPPAD_HOME) + + FIND_PATH(CPPAD_INCLUDE_DIR NAMES cppad/cppad.hpp + PATHS "${CPPAD_HOME}" + NO_DEFAULT_PATH) + + FIND_LIBRARY(CPPAD_IPOPT_LIBRARY + cppad_ipopt + PATHS "${CPPAD_HOME}/lib" + NO_DEFAULT_PATH) + + SET(CPPAD_INCLUDE_DIRS ${CPPAD_INCLUDE_DIR}) + SET(CPPAD_LIBRARIES ${CPPAD_IPOPT_LIBRARY}) + +ELSE() + + FIND_PACKAGE(PkgConfig) + + IF( PKG_CONFIG_FOUND ) + pkg_check_modules( CPPAD QUIET cppad) + ENDIF() + + + IF( NOT CPPAD_FOUND ) + FIND_PATH(CPPAD_INCLUDE_DIR NAMES cppad/cppad.hpp + HINTS "$ENV{CPPAD_HOME}" + "/usr/include" ) + + FIND_LIBRARY(CPPAD_IPOPT_LIBRARY + cppad_ipopt + HINTS "$ENV{CPPAD_HOME}/lib" + "/usr/lib" ) + + IF( CPPAD_INCLUDE_DIR ) + SET(CPPAD_INCLUDE_DIRS ${CPPAD_INCLUDE_DIR}) + ENDIF() + + IF( CPPAD_IPOPT_LIBRARY ) + SET(CPPAD_LIBRARIES ${CPPAD_IPOPT_LIBRARY}) + ENDIF() + + INCLUDE(FindPackageHandleStandardArgs) + # handle the QUIETLY and REQUIRED arguments and set CPPAD_FOUND to TRUE + # if all listed variables are TRUE + find_package_handle_standard_args(CppAD DEFAULT_MSG + CPPAD_INCLUDE_DIRS) + + MARK_AS_ADVANCED(CPPAD_INCLUDE_DIRS CPPAD_LIBRARIES) + + ENDIF() +ENDIF() + + +IF( CPPAD_FOUND AND NOT CPPAD_FIND_QUIETLY ) + MESSAGE(STATUS "package CppAD found") +ENDIF() + diff --git a/ct_core/cmake/FindCppADCG.cmake b/ct_core/cmake/FindCppADCG.cmake new file mode 100644 index 000000000..cdc183c42 --- /dev/null +++ b/ct_core/cmake/FindCppADCG.cmake @@ -0,0 +1,53 @@ + +IF (CPPADCG_INCLUDES AND CPPADCG_LIBRARIES) + SET(CPPADCG_FIND_QUIETLY TRUE) +ENDIF () + + +IF(DEFINED CPPADCG_HOME) + + FIND_PATH(CPPADCG_INCLUDE_DIR NAMES cppadcg/cppadcg.hpp + PATHS "${CPPADCG_HOME}" + NO_DEFAULT_PATH) + + SET(CPPADCG_INCLUDE_DIRS ${CPPADCG_INCLUDE_DIR}) + SET(CPPADCG_LIBRARIES ${CPPADCG_LIBRARY}) + +ELSE() + + FIND_PACKAGE(PkgConfig) + + IF( PKG_CONFIG_FOUND ) + pkg_check_modules( CPPADCG QUIET cppadcg) + ENDIF() + + + IF( NOT CPPADCG_FOUND ) + FIND_PATH(CPPADCG_INCLUDE_DIR NAMES cppadcg/cppadcg.hpp + HINTS "$ENV{CPPADCG_HOME}" + "/usr/include" ) + + IF( CPPADCG_INCLUDE_DIR ) + SET(CPPADCG_INCLUDE_DIRS ${CPPADCG_INCLUDE_DIR} ${CLANG_INCLUDE_DIRS}) + ENDIF() + + IF( CPPADCG_LIBRARY ) + SET(CPPADCG_LIBRARIES ${CPPADCG_LIBRARY}) + ENDIF() + + INCLUDE(FindPackageHandleStandardArgs) + # handle the QUIETLY and REQUIRED arguments and set CPPADCG_FOUND to TRUE + # if all listed variables are TRUE + find_package_handle_standard_args(CppAD DEFAULT_MSG + CPPADCG_INCLUDE_DIRS) + + MARK_AS_ADVANCED(CPPADCG_INCLUDE_DIRS CPPADCG_LIBRARIES) + + ENDIF() +ENDIF() + + +IF( CPPADCG_FOUND AND NOT CPPADCG_FIND_QUIETLY ) + MESSAGE(STATUS "package CppADCG found") +ENDIF() + diff --git a/ct_core/cmake/Findclang.cmake b/ct_core/cmake/Findclang.cmake new file mode 100644 index 000000000..12f7fab2a --- /dev/null +++ b/ct_core/cmake/Findclang.cmake @@ -0,0 +1,51 @@ + +UNSET(CLANG_INCLUDE_DIRS CACHE) +UNSET(CLANG_LIBS CACHE) + +IF(NOT LLVM_INCLUDE_DIRS OR NOT LLVM_LIBRARY_DIRS) + SET(CLANG_FOUND FALSE) + MESSAGE(STATUS "No LLVM and Clang support, requires LLVM") + RETURN() +ENDIF() + +MACRO(findClangStaticLib _libname_) + UNSET(CLANG_${_libname_}_LIB CACHE) + IF(LLVM_LIBRARY_DIRS) + FIND_LIBRARY(CLANG_${_libname_}_LIB ${_libname_} PATH ${LLVM_LIBRARY_DIRS}) + ELSE() + FIND_LIBRARY(CLANG_${_libname_}_LIB ${_libname_} ${LLVM_LIBRARY_DIRS} ${CLANG_LIBRARY_DIRS}) + ENDIF() + + + MARK_AS_ADVANCED(CLANG_${_libname_}_LIB) + IF(CLANG_${_libname_}_LIB) + SET(CLANG_LIBS ${CLANG_LIBS} ${CLANG_${_libname_}_LIB}) + ENDIF() +ENDMACRO() + +findClangStaticLib(clang NAMES clang libclang) + +# Clang shared library provides just the limited C interface, so it +# can not be used. We look for the static libraries. +SET(CLANG_LIBNAMES clangCodeGen clangFrontendTool clangFrontend clangDriver clangSerialization clangTooling + clangParse clangSema clangChecker clangRewrite clangRewriteFrontend + clangStaticAnalyzerFrontend clangStaticAnalyzerCheckers + clangStaticAnalyzerCore clangAnalysis clangARCMigrate clangEdit clangAST clangASTMatchers clangLex + clangBasic clangRewriteCore) + +foreach(LIBNAME ${CLANG_LIBNAMES}) + findClangStaticLib(${LIBNAME}) +endforeach() + + +UNSET(CLANG_INCLUDE_DIRS CACHE) +FIND_PATH(CLANG_INCLUDE_DIRS clang/Basic/Version.h HINTS ${LLVM_INCLUDE_DIRS}) + +INCLUDE(FindPackageHandleStandardArgs) +# handle the QUIETLY and REQUIRED arguments and set CLANG_FOUND to TRUE +# if all listed variables are TRUE +find_package_handle_standard_args(CLANG DEFAULT_MSG + CLANG_INCLUDE_DIRS + CLANG_LIBS) + +MARK_AS_ADVANCED(CLANG_INCLUDE_DIRS CLANG_LIBS) \ No newline at end of file diff --git a/ct_core/cmake/Findllvm.cmake b/ct_core/cmake/Findllvm.cmake new file mode 100644 index 000000000..7c2c3cebc --- /dev/null +++ b/ct_core/cmake/Findllvm.cmake @@ -0,0 +1,136 @@ + +IF(LLVM_FIND_VERSION AND LLVM_FIND_VERSION_MAJOR LESS 4 AND NOT LLVM_FIND_VERSION_MINOR) + MESSAGE(FATAL_ERROR "When requesting a specific version of LLVM higher or equal to 7.0 you should only proide the major version, on LLVM versions lower than 4.0, you must provide at least the major and minor version numbers, e.g., 3.8") +ENDIF() + +# Lets make sure cache doesn't ruin the day +UNSET(LLVM_CONFIG CACHE) +UNSET(LLVM_FOUND CACHE) +UNSET(LLVM_FOUND CACHE) +UNSET(LLVM_INCLUDE_DIRS CACHE) +UNSET(LLVM_LIBRARY_DIRS CACHE) +UNSET(LLVM_CFLAGS CACHE) +UNSET(LLVM_LDFLAGS CACHE) +UNSET(LLVM_MODULE_LIBS CACHE) + + +MACRO(find_llvm_iteratively) + IF(NOT LLVM_CONFIG AND NOT LLVM_FIND_VERSION_EXACT) + SET(_LLVM_KNOWN_VERSIONS ${LLVM_ADDITIONAL_VERSIONS} "8" "7" "6.0" "5.0" "4.0" "3.8" "3.7" "3.6" "3.5" "3.4" "3.3" "3.2") + + # Select acceptable versions. + FOREACH(version ${_LLVM_KNOWN_VERSIONS}) + + IF(NOT "${version}" VERSION_LESS "${LLVM_FIND_VERSION_MAJOR}.${LLVM_FIND_VERSION_MINOR}") + FIND_PROGRAM(LLVM_CONFIG "llvm-config-${version}") + IF(LLVM_CONFIG) + BREAK() # Found suitable version + ENDIF() + ELSE() + BREAK() # Lower version than requested + ENDIF() + ENDFOREACH() + ENDIF() +ENDMACRO() + + +IF(LLVM_FIND_VERSION) + FIND_PROGRAM(LLVM_CONFIG "llvm-config-${LLVM_VERSION}") + + IF(NOT LLVM_CONFIG) # LLVM_FIND_VERSION_EXACT or failed to find using previous search + # Lets try to find the exact specified version + FIND_PROGRAM(LLVM_CONFIG "llvm-config-${LLVM_FIND_VERSION_MAJOR}.${LLVM_FIND_VERSION_MINOR}") + + IF(NOT LLVM_CONFIG AND NOT LLVM_FIND_VERSION_EXACT) + find_llvm_iteratively() + ENDIF() + ENDIF() +ELSE() + FIND_PROGRAM(LLVM_CONFIG llvm-config) + + IF(NOT LLVM_CONFIG) + find_llvm_iteratively() + ENDIF() +ENDIF() + + +IF(LLVM_CONFIG) + MESSAGE(STATUS "llvm-config found at: ${LLVM_CONFIG}") +ELSE() + MESSAGE(STATUS "Could NOT find llvm-config") + SET(LLVM_FOUND FALSE) + return() +ENDIF() + +EXECUTE_PROCESS(COMMAND ${LLVM_CONFIG} --version + OUTPUT_VARIABLE LLVM_VERSION + OUTPUT_STRIP_TRAILING_WHITESPACE) + +STRING(REGEX REPLACE "^([0-9]+)\\.([0-9]+).*" "\\1" + LLVM_VERSION_MAJOR + "${LLVM_VERSION}") + +STRING(REGEX REPLACE "^([0-9]+)\\.([0-9]+).*" "\\2" + LLVM_VERSION_MINOR + "${LLVM_VERSION}") + +# Version validation +IF(LLVM_FIND_VERSION) + IF(LLVM_FIND_VERSION_EXACT) + IF(NOT ${LLVM_VERSION} VERSION_EQUAL "${LLVM_FIND_VERSION_MAJOR}.${LLVM_FIND_VERSION_MINOR}") + MESSAGE(FATAL_ERROR "Failed to find the specified version of LLVM") + ENDIF() + ELSEIF(${LLVM_VERSION} VERSION_LESS "${LLVM_FIND_VERSION_MAJOR}.${LLVM_FIND_VERSION_MINOR}") + MESSAGE(FATAL_ERROR "Failed to find a LLVM version equal or higher than ${LLVM_FIND_VERSION_MAJOR}.${LLVM_FIND_VERSION_MINOR}") + ENDIF() +ENDIF() + + +EXECUTE_PROCESS(COMMAND ${LLVM_CONFIG} --includedir + OUTPUT_VARIABLE LLVM_INCLUDE_DIRS + OUTPUT_STRIP_TRAILING_WHITESPACE) + +EXECUTE_PROCESS(COMMAND ${LLVM_CONFIG} --libdir + OUTPUT_VARIABLE LLVM_LIBRARY_DIRS + OUTPUT_STRIP_TRAILING_WHITESPACE) + +EXECUTE_PROCESS(COMMAND ${LLVM_CONFIG} --cppflags + OUTPUT_VARIABLE LLVM_CFLAGS + OUTPUT_STRIP_TRAILING_WHITESPACE) + +IF(LLVM_CFLAGS MATCHES "\\-DNDEBUG") + SET(LLVM_WITH_NDEBUG 1) +ELSE() + SET(LLVM_WITH_NDEBUG 0) +ENDIF() + +STRING(REPLACE "-DNDEBUG" "" + LLVM_CFLAGS_NO_NDEBUG + ${LLVM_CFLAGS}) + +FIND_LIBRARY(LLVM_MODULE_LIBS LLVM-${LLVM_VERSION_MAJOR}.${LLVM_VERSION_MINOR} ${LLVM_LIBRARY_DIRS}) +IF(NOT LLVM_MODULE_LIBS) + EXECUTE_PROCESS(COMMAND ${LLVM_CONFIG} --libs + OUTPUT_VARIABLE LLVM_MODULE_LIBS + OUTPUT_STRIP_TRAILING_WHITESPACE) +ENDIF() + +EXECUTE_PROCESS(COMMAND ${LLVM_CONFIG} --ldflags + OUTPUT_VARIABLE LLVM_LDFLAGS + OUTPUT_STRIP_TRAILING_WHITESPACE) + +INCLUDE(FindPackageHandleStandardArgs) +# handle the QUIETLY and REQUIRED arguments and set LLVM_FOUND to TRUE +# if all listed variables are TRUE +find_package_handle_standard_args(LLVM DEFAULT_MSG + LLVM_INCLUDE_DIRS + LLVM_LIBRARY_DIRS + LLVM_CFLAGS + LLVM_LDFLAGS + LLVM_MODULE_LIBS) + +MARK_AS_ADVANCED(LLVM_INCLUDE_DIRS + LLVM_LIBRARY_DIRS + LLVM_CFLAGS + LLVM_LDFLAGS + LLVM_MODULE_LIBS) diff --git a/ct_core/doc/ct_core.doxyfile b/ct_core/doc/ct_core.doxyfile index cf3c62657..d4e76199e 100644 --- a/ct_core/doc/ct_core.doxyfile +++ b/ct_core/doc/ct_core.doxyfile @@ -38,13 +38,13 @@ PROJECT_NAME = " " # could be handy for archiving the generated documentation or if some version # control system is used. -PROJECT_NUMBER = 3.0.1 +PROJECT_NUMBER = 3.0.2 # Using the PROJECT_BRIEF tag one can provide an optional one line description # for a project that appears at the top of each page and should give viewer a # quick idea about the purpose of the project. Keep the description short. -PROJECT_BRIEF = " - 3.0.1 core module." +PROJECT_BRIEF = " - 3.0.2 core module." # With the PROJECT_LOGO tag one can specify an logo or icon that is included in # the documentation. The maximum height of the logo should not exceed 55 pixels diff --git a/ct_core/examples/include/ct/core/examples/Masspoint.h b/ct_core/examples/include/ct/core/examples/Masspoint.h index 48bd8db12..9702d8167 100644 --- a/ct_core/examples/include/ct/core/examples/Masspoint.h +++ b/ct_core/examples/include/ct/core/examples/Masspoint.h @@ -15,16 +15,21 @@ class Masspoint : public ct::core::System<2> { public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + static const size_t STATE_DIM = 2; // constructor Masspoint(double mass, double d) : mass_(mass), d_(d) {} + // copy constructor Masspoint(const Masspoint& other) : mass_(other.mass_), d_(other.d_) {} + // destructor - ~Masspoint() {} - // clone method - Masspoint* clone() + ~Masspoint() = default; + + // clone method for deep copying + Masspoint* clone() const override { return new Masspoint(*this); // calls copy constructor } diff --git a/ct_core/include/ct/core/Math-impl b/ct_core/include/ct/core/Math-impl index 0b9dc8fc9..52f2d3d39 100644 --- a/ct_core/include/ct/core/Math-impl +++ b/ct_core/include/ct/core/Math-impl @@ -5,5 +5,5 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once -// put implementation files here +#include "math/DerivativesCppadJIT-impl.h" diff --git a/ct_core/include/ct/core/internal/autodiff/CGHelpers.h b/ct_core/include/ct/core/internal/autodiff/CGHelpers.h index 2073c5319..fbaefbfdf 100644 --- a/ct_core/include/ct/core/internal/autodiff/CGHelpers.h +++ b/ct_core/include/ct/core/internal/autodiff/CGHelpers.h @@ -5,22 +5,22 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once +#ifdef CPPADCG + #include "SparsityPattern.h" -#include namespace ct { namespace core { namespace internal { + //! Utility class for Auto-Diff code generation class CGHelpers { public: - //! default constructor - CGHelpers(){}; + CGHelpers() = default; - //! destructor - virtual ~CGHelpers(){}; + virtual ~CGHelpers() = default; //! generate source code for Jacobian /*! @@ -329,6 +329,9 @@ class CGHelpers } }; + } /* namespace internal */ } /* namespace core */ } /* namespace ct */ + +#endif \ No newline at end of file diff --git a/ct_core/include/ct/core/internal/autodiff/CppadParallel.h b/ct_core/include/ct/core/internal/autodiff/CppadParallel.h index 16ee4eac7..4e24507bf 100644 --- a/ct_core/include/ct/core/internal/autodiff/CppadParallel.h +++ b/ct_core/include/ct/core/internal/autodiff/CppadParallel.h @@ -10,6 +10,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) namespace ct { namespace core { +#ifdef CPPAD + /** * @brief This class provides static methods to initialize a parallel * section containing CppAD objects @@ -27,6 +29,7 @@ class CppadParallel static void initParallel(size_t numThreads) { CppadParallel::getInstance().initParallelImpl(numThreads); } static void resetParallel() { CppadParallel::getInstance().resetParallelImpl(); } + private: /** * @brief Call this function before entering a parallel section @@ -99,5 +102,7 @@ class CppadParallel CppadParallel(CppadParallel const&) = delete; void operator=(CppadParallel const&) = delete; }; -} -} + +#endif +} // namespace core +} // namespace ct diff --git a/ct_core/include/ct/core/internal/autodiff/SparsityPattern.h b/ct_core/include/ct/core/internal/autodiff/SparsityPattern.h index fa03347b7..ea4bd83ea 100644 --- a/ct_core/include/ct/core/internal/autodiff/SparsityPattern.h +++ b/ct_core/include/ct/core/internal/autodiff/SparsityPattern.h @@ -5,6 +5,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once +#ifdef CPPAD + #include #include @@ -114,3 +116,5 @@ class SparsityPattern } /* namespace internal */ } /* namespace core */ } /* namespace ct */ + +#endif diff --git a/ct_core/include/ct/core/math/DerivativesCppad.h b/ct_core/include/ct/core/math/DerivativesCppad.h index 3947d42a6..cbdffd047 100644 --- a/ct_core/include/ct/core/math/DerivativesCppad.h +++ b/ct_core/include/ct/core/math/DerivativesCppad.h @@ -10,6 +10,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) namespace ct { namespace core { +#ifdef CPPAD + //! Jacobian using Auto-Diff Codegeneration /*! * Uses Auto-Diff code generation to compute the Jacobian \f$ J(x_s) = \frac{df}{dx} |_{x=x_s} \f$ of @@ -198,5 +200,7 @@ class DerivativesCppad : public Derivatives // double CppAD::ADFun adCppadFun_; }; +#endif + } /* namespace core */ } /* namespace ct */ diff --git a/ct_core/include/ct/core/math/DerivativesCppadCG.h b/ct_core/include/ct/core/math/DerivativesCppadCG.h index 351ce4835..f1081c9cd 100644 --- a/ct_core/include/ct/core/math/DerivativesCppadCG.h +++ b/ct_core/include/ct/core/math/DerivativesCppadCG.h @@ -11,6 +11,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) namespace ct { namespace core { +#ifdef CPPADCG + //! Jacobian using Auto-Diff Codegeneration /*! * Uses Auto-Diff code generation to compute the Jacobian \f$ J(x_s) = \frac{df}{dx} |_{x=x_s} \f$ of @@ -272,5 +274,7 @@ class DerivativesCppadCG size_t tmpVarCount_; //! number of temporary variables in the source code }; +#endif + } /* namespace core */ } /* namespace ct */ diff --git a/ct_core/include/ct/core/math/DerivativesCppadJIT-impl.h b/ct_core/include/ct/core/math/DerivativesCppadJIT-impl.h new file mode 100644 index 000000000..60e4b2e14 --- /dev/null +++ b/ct_core/include/ct/core/math/DerivativesCppadJIT-impl.h @@ -0,0 +1,484 @@ +/********************************************************************************************************************** +This file is part of the Control Toolbox (https://github.com/ethz-adrl/control-toolbox), copyright by ETH Zurich. +Licensed under the BSD-2 license (see LICENSE file in main directory) +**********************************************************************************************************************/ + +#pragma once + +#ifdef CPPADCG + +namespace ct { +namespace core { + + +template +DerivativesCppadJIT::DerivativesCppadJIT(FUN_TYPE_CG& f, int inputDim, int outputDim) + : DerivativesBase(), + cgStdFun_(f), + inputDim_(inputDim), + outputDim_(outputDim), + compiled_(false), + libName_(""), + dynamicLib_(nullptr) +#ifdef LLVM_VERSION_MAJOR + , + llvmModelLib_(nullptr) +#endif +{ + update(f, inputDim, outputDim); +} + +template +DerivativesCppadJIT::DerivativesCppadJIT(const DerivativesCppadJIT& arg) + : DerivativesBase(arg), + cgStdFun_(arg.cgStdFun_), + inputDim_(arg.inputDim_), + outputDim_(arg.outputDim_), + compiled_(arg.compiled_), + libName_(arg.libName_), + dynamicLib_(nullptr) +#ifdef LLVM_VERSION_MAJOR + , + llvmModelLib_(nullptr) +#endif +{ + cgCppadFun_ = arg.cgCppadFun_; + if (compiled_) + { + if (arg.dynamicLib_) // in case of dynamic libraries + { + dynamicLib_ = internal::CGHelpers::loadDynamicLibCppad(libName_); + model_ = std::shared_ptr>(dynamicLib_->model(libName_)); + } +#ifdef LLVM_VERSION_MAJOR + else if (arg.llvmModelLib_) // in case of regular JIT without dynamic lib + { + throw std::runtime_error("DerivativesCppadJIT: cloning of LLVM-JIT libraries is currently not supported."); + llvmModelLib_ = arg.llvmModelLib_; // TODO: this is not clean, we need to properly clone the llvm model lib + model_ = std::shared_ptr>(llvmModelLib_->model(libName_)); + } +#endif + else + throw std::runtime_error("DerivativesCppadJIT: undefined behaviour in copy constructor."); + } +} + +template +void DerivativesCppadJIT::update(FUN_TYPE_CG& f, const size_t inputDim, const size_t outputDim) +{ + cgStdFun_ = f; + outputDim_ = outputDim; + inputDim_ = inputDim; + if (outputDim_ > 0 && inputDim_ > 0) + { + recordCg(); + compiled_ = false; + libName_ = ""; + dynamicLib_ = nullptr; + model_ = nullptr; + } +} + +template +auto DerivativesCppadJIT::clone() const -> DerivativesCppadJIT* +{ + return new DerivativesCppadJIT(*this); +} + +template +auto DerivativesCppadJIT::forwardZero(const Eigen::VectorXd& x) -> OUT_TYPE_D +{ + if (compiled_) + { + assert(model_->isForwardZeroAvailable() == true); + return model_->ForwardZero(x); + } + else + { + throw std::runtime_error("Error: Compile the library first by calling compileJIT(..)"); + } +} + +template +auto DerivativesCppadJIT::jacobian(const Eigen::VectorXd& x) -> JAC_TYPE_D +{ + if (outputDim_ <= 0) + throw std::runtime_error("Outdim dim smaller 0; Define output dim in DerivativesCppad constructor"); + + + Eigen::VectorXd jac; + if (compiled_) + { + assert(model_->isJacobianAvailable() == true); + jac = model_->Jacobian(x); + JAC_TYPE_D out(outputDim_, x.rows()); + out = JAC_TYPE_ROW_MAJOR::Map(jac.data(), outputDim_, x.rows()); + return out; + } + else + throw std::runtime_error("Error: Compile the library first by calling compileJIT(..)"); +} + +template +void DerivativesCppadJIT::sparseJacobian(const Eigen::VectorXd& x, + Eigen::VectorXd& jac, + Eigen::VectorXi& iRow, + Eigen::VectorXi& jCol) +{ + if (outputDim_ <= 0) + throw std::runtime_error("Outdim dim smaller 0; Define output dim in DerivativesCppad constructor"); + + if (compiled_) + { + assert(model_->isSparseJacobianAvailable() == true); + std::vector input(x.data(), x.data() + x.rows() * x.cols()); + std::vector output; + model_->SparseJacobian(input, output, sparsityRowsJacobian_, sparsityColsJacobian_); + jac = Eigen::Map(output.data(), output.size(), 1); + iRow = sparsityRowsJacobianEigen_; + jCol = sparsityColsJacobianEigen_; + } + else + throw std::runtime_error("Error: Compile the library first by calling compileJIT(..)"); +} + +template +Eigen::VectorXd DerivativesCppadJIT::sparseJacobianValues(const Eigen::VectorXd& x) +{ + if (outputDim_ <= 0) + throw std::runtime_error("Outdim dim smaller 0; Define output dim in DerivativesCppad constructor"); + + if (compiled_) + { + assert(model_->isSparseJacobianAvailable() == true); + std::vector input(x.data(), x.data() + x.rows() * x.cols()); + std::vector output; + model_->SparseJacobian(input, output, sparsityRowsJacobian_, sparsityColsJacobian_); + return Eigen::Map(output.data(), output.size(), 1); + } + else + throw std::runtime_error("Error: Compile the library first by calling compileJIT(..)"); +} + +template +auto DerivativesCppadJIT::hessian(const Eigen::VectorXd& x, const Eigen::VectorXd& lambda) + -> HES_TYPE_D +{ + if (outputDim_ <= 0) + throw std::runtime_error("Outdim dim smaller 0; Define output dim in DerivativesCppad constructor"); + + if (compiled_) + { + assert(model_->isHessianAvailable() == true); + Eigen::VectorXd hessian = model_->Hessian(x, lambda); + HES_TYPE_D out(x.rows(), x.rows()); + out = HES_TYPE_ROW_MAJOR::Map(hessian.data(), x.rows(), x.rows()); + return out; + } + else + { + throw std::runtime_error("Error: Compile the library first by calling compileJIT(..)"); + } +} + +template +void DerivativesCppadJIT::sparseHessian(const Eigen::VectorXd& x, + const Eigen::VectorXd& lambda, + Eigen::VectorXd& hes, + Eigen::VectorXi& iRow, + Eigen::VectorXi& jCol) +{ + if (outputDim_ <= 0) + throw std::runtime_error("Outdim dim smaller 0; Define output dim in DerivativesCppad constructor"); + + if (compiled_) + { + assert(model_->isSparseJacobianAvailable() == true); + std::vector input(x.data(), x.data() + x.rows() * x.cols()); + std::vector inputLambda(lambda.data(), lambda.data() + lambda.rows() * lambda.cols()); + std::vector output; + model_->SparseHessian(input, inputLambda, output, sparsityRowsHessian_, sparsityColsHessian_); + hes = Eigen::Map(output.data(), output.size(), 1); + iRow = sparsityRowsHessianEigen_; + jCol = sparsityColsHessianEigen_; + } + else + throw std::runtime_error("Error: Compile the library first by calling compileJIT(..)"); +} + +template +Eigen::VectorXd DerivativesCppadJIT::sparseHessianValues(const Eigen::VectorXd& x, + const Eigen::VectorXd& lambda) +{ + if (outputDim_ <= 0) + throw std::runtime_error("Outdim dim smaller 0; Define output dim in DerivativesCppad constructor"); + + if (compiled_) + { + assert(model_->isSparseHessianAvailable() == true); + std::vector input(x.data(), x.data() + x.rows() * x.cols()); + std::vector inputLambda(lambda.data(), lambda.data() + lambda.rows() * lambda.cols()); + std::vector output; + model_->SparseHessian(input, inputLambda, output, sparsityRowsHessian_, sparsityColsHessian_); + return Eigen::Map(output.data(), output.size(), 1); + } + else + throw std::runtime_error("Error: Compile the library first by calling compileJIT(..)"); +} + +template +Eigen::Matrix DerivativesCppadJIT::getSparsityPatternJacobian() +{ + assert(model_->isJacobianSparsityAvailable() == true); + + std::vector sparsityVec = model_->JacobianSparsityBool(); + Eigen::Matrix sparsityMat(outputDim_, inputDim_); + + assert((int)(sparsityVec.size()) == outputDim_ * inputDim_); + for (int row = 0; row < outputDim_; ++row) + for (int col = 0; col < inputDim_; ++col) + sparsityMat(row, col) = sparsityVec[col + row * inputDim_]; + + return sparsityMat; +} + +template +Eigen::Matrix DerivativesCppadJIT::getSparsityPatternHessian() +{ + assert(model_->isHessianSparsityAvailable() == true); + + std::vector sparsityVec = model_->HessianSparsityBool(); + Eigen::Matrix sparsityMat(inputDim_, inputDim_); + + assert(sparsityVec.size() == inputDim_ * inputDim_); + for (int row = 0; row < inputDim_; ++row) + for (int col = 0; col < inputDim_; ++col) + { + sparsityMat(row, col) = sparsityVec[col + row * inputDim_]; + } + + return sparsityMat; +} + +template +void DerivativesCppadJIT::getSparsityPatternJacobian(Eigen::VectorXi& rows, Eigen::VectorXi& columns) +{ + assert(model_->isJacobianSparsityAvailable() == true); + + rows = sparsityRowsJacobianEigen_; + columns = sparsityColsJacobianEigen_; +} + +template +size_t DerivativesCppadJIT::getNumNonZerosJacobian() +{ + assert(model_->isJacobianSparsityAvailable() == true); + return sparsityRowsJacobian_.size(); +} + +template +size_t DerivativesCppadJIT::getNumNonZerosHessian() +{ + assert(model_->isJacobianSparsityAvailable() == true); + return sparsityRowsHessian_.size(); +} + +template +void DerivativesCppadJIT::getSparsityPatternHessian(Eigen::VectorXi& rows, Eigen::VectorXi& columns) +{ + assert(model_->isHessianSparsityAvailable() == true); + + rows = sparsityRowsHessianEigen_; + columns = sparsityColsHessianEigen_; +} + +template +void DerivativesCppadJIT::compileJIT(const DerivativesCppadSettings& settings, + const std::string& libName, + bool verbose) +{ + if (compiled_) + return; + + struct timespec ts; + clock_gettime(CLOCK_MONOTONIC, &ts); + + // assigning a unique identifier to the library in order to avoid race conditions in JIT + std::string uniqueID = + std::to_string(std::hash()(std::this_thread::get_id())) + "_" + std::to_string(ts.tv_nsec); + + libName_ = libName + uniqueID; + + CppAD::cg::ModelCSourceGen cgen(cgCppadFun_, libName_); + + cgen.setMultiThreading(settings.multiThreading_); + cgen.setCreateForwardZero(settings.createForwardZero_); + cgen.setCreateForwardOne(settings.createForwardOne_); + cgen.setCreateReverseOne(settings.createReverseOne_); + cgen.setCreateReverseTwo(settings.createReverseTwo_); + cgen.setCreateJacobian(settings.createJacobian_); + cgen.setCreateSparseJacobian(settings.createSparseJacobian_); + cgen.setCreateHessian(settings.createHessian_); + cgen.setCreateSparseHessian(settings.createSparseHessian_); + cgen.setMaxAssignmentsPerFunc(settings.maxAssignements_); + + CppAD::cg::ModelLibraryCSourceGen libcgen(cgen); + + if (settings.useDynamicLibrary_) + { + std::string tempDir = "cppad_temp" + uniqueID; + if (verbose) + { + std::cout << "DerivativesCppadJIT: starting to compile dynamic library" << libName_ << std::endl; + std::cout << "DerivativesCppadJIT: in temporary directory " << tempDir << std::endl; + } + + // compile a dynamic library + CppAD::cg::DynamicModelLibraryProcessor p(libcgen, libName_); + + if (settings.compiler_ == DerivativesCppadSettings::GCC) + { + CppAD::cg::GccCompiler compiler; + compiler.setTemporaryFolder(tempDir); + dynamicLib_ = std::shared_ptr>(p.createDynamicLibrary(compiler)); + } + else if (settings.compiler_ == DerivativesCppadSettings::CLANG) + { + CppAD::cg::ClangCompiler compiler; + compiler.setTemporaryFolder(tempDir); + dynamicLib_ = std::shared_ptr>(p.createDynamicLibrary(compiler)); + } + else + throw std::runtime_error("Unknown compiler type for dynamic library, support only gcc and clang."); + + // extract model + model_ = std::shared_ptr>(dynamicLib_->model(libName_)); + } + else // use regular JIT + { + if (verbose) + { + std::cout << "DerivativesCppadJIT: starting to compile with LLVM library " << libName_ << std::endl; + } +#ifdef LLVM_VERSION_MAJOR + // JIT compile source code + CppAD::cg::LlvmModelLibraryProcessor p(libcgen); + llvmModelLib_ = p.create(); + + //extract model + model_ = std::shared_ptr>(llvmModelLib_->model(libName_)); +#else + throw std::runtime_error("DerivativesCppadJIT: LLVM not installed."); +#endif + } + + + if (settings.generateSourceCode_) + { + if (verbose) + { + std::cout << "DerivativesCppadJIT: generating source-code... " << libName_ << std::endl; + } + CppAD::cg::SaveFilesModelLibraryProcessor p2(libcgen); + p2.saveSources(); + } + + compiled_ = true; + + if (model_->isJacobianSparsityAvailable()) + { + if (verbose) + std::cout << "DerivativesCppadJIT: updating Jacobian sparsity pattern" << std::endl; + + model_->JacobianSparsity(sparsityRowsJacobian_, sparsityColsJacobian_); + sparsityRowsJacobianEigen_.resize(sparsityRowsJacobian_.size()); //rowsTmp.resize(rowsVec.size()); + sparsityColsJacobianEigen_.resize(sparsityColsJacobian_.size()); //colsTmp.resize(rowsVec.size()); + + Eigen::Matrix rowsSizeT; + rowsSizeT.resize(sparsityRowsJacobian_.size()); + Eigen::Matrix colsSizeT; + colsSizeT.resize(sparsityColsJacobian_.size()); + + rowsSizeT = Eigen::Map>( + sparsityRowsJacobian_.data(), sparsityRowsJacobian_.size(), 1); + colsSizeT = Eigen::Map>( + sparsityColsJacobian_.data(), sparsityColsJacobian_.size(), 1); + + sparsityRowsJacobianEigen_ = rowsSizeT.cast(); + sparsityColsJacobianEigen_ = colsSizeT.cast(); + } + + if (model_->isHessianSparsityAvailable()) + { + if (verbose) + std::cout << "DerivativesCppadJIT: updating Hessian sparsity pattern" << std::endl; + + model_->HessianSparsity(sparsityRowsHessian_, sparsityColsHessian_); + sparsityRowsHessianEigen_.resize(sparsityRowsHessian_.size()); //rowsTmp.resize(rowsVec.size()); + sparsityColsHessianEigen_.resize(sparsityColsHessian_.size()); //colsTmp.resize(rowsVec.size()); + + Eigen::Matrix rowsSizeT; + rowsSizeT.resize(sparsityRowsHessian_.size()); + Eigen::Matrix colsSizeT; + colsSizeT.resize(sparsityColsHessian_.size()); + + rowsSizeT = Eigen::Map>( + sparsityRowsHessian_.data(), sparsityRowsHessian_.size(), 1); + colsSizeT = Eigen::Map>( + sparsityColsHessian_.data(), sparsityColsHessian_.size(), 1); + + sparsityRowsHessianEigen_ = rowsSizeT.cast(); + sparsityColsHessianEigen_ = colsSizeT.cast(); + } + + if (verbose) + std::cout << "DerivativesCppadJIT: compileJIT() completed." << std::endl; +} + +template +auto DerivativesCppadJIT::getDynamicLib() -> const std::shared_ptr> +{ + if (dynamicLib_) + return dynamicLib_; + else + throw std::runtime_error("DerivativesCppADJIT: dynamic lib not compiled."); +} + +#ifdef LLVM_VERSION_MAJOR +template +auto DerivativesCppadJIT::getLlvmLib() -> const std::shared_ptr> +{ + if (llvmModelLib_) + return llvmModelLib_; + else + throw std::runtime_error("DerivativesCppADJIT: llvm library not available."); +} +#endif + +template +void DerivativesCppadJIT::recordCg() +{ + // input vector, needs to be dynamic size + Eigen::Matrix x(inputDim_); + + // declare x as independent + CppAD::Independent(x); + + // output vector, needs to be dynamic size + Eigen::Matrix y(outputDim_); + + y = cgStdFun_(x); + + // store operation sequence in f: x -> y and stop recording + CppAD::ADFun fCodeGen(x, y); + + fCodeGen.optimize(); + + cgCppadFun_ = fCodeGen; +} + + +} /* namespace core */ +} /* namespace ct */ + +#endif \ No newline at end of file diff --git a/ct_core/include/ct/core/math/DerivativesCppadJIT.h b/ct_core/include/ct/core/math/DerivativesCppadJIT.h index dbb6b566a..55efcb873 100644 --- a/ct_core/include/ct/core/math/DerivativesCppadJIT.h +++ b/ct_core/include/ct/core/math/DerivativesCppadJIT.h @@ -5,14 +5,19 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once +#ifdef CPPADCG + #include #include #include #include +#include + namespace ct { namespace core { + //! Jacobian using Auto-Diff Codegeneration /*! * Uses Auto-Diff code generation to compute the Jacobian \f$ J(x_s) = \frac{df}{dx} |_{x=x_s} \f$ of @@ -62,33 +67,14 @@ class DerivativesCppadJIT : public Derivatives // doub * @param[in] outputDim outputDim output dimension, must be specified if * template parameter IN_DIM is -1 (dynamic) */ - DerivativesCppadJIT(FUN_TYPE_CG& f, int inputDim = IN_DIM, int outputDim = OUT_DIM) - : DerivativesBase(), cgStdFun_(f), inputDim_(inputDim), outputDim_(outputDim), compiled_(false), libName_("") - { - update(f, inputDim, outputDim); - } + DerivativesCppadJIT(FUN_TYPE_CG& f, int inputDim = IN_DIM, int outputDim = OUT_DIM); /*! * @brief copy constructor * @param arg instance to copy * @note It is important to not only copy the pointer to the dynamic library, but to load the library properly instead. */ - DerivativesCppadJIT(const DerivativesCppadJIT& arg) - : DerivativesBase(arg), - cgStdFun_(arg.cgStdFun_), - inputDim_(arg.inputDim_), - outputDim_(arg.outputDim_), - compiled_(arg.compiled_), - libName_(arg.libName_) - { - cgCppadFun_ = arg.cgCppadFun_; - if (compiled_) - { - dynamicLib_ = internal::CGHelpers::loadDynamicLibCppad(libName_); - model_ = - std::shared_ptr>(dynamicLib_->model("DerivativesCppad" + libName_)); - } - } + DerivativesCppadJIT(const DerivativesCppadJIT& arg); //! update the Jacobian with a new function @@ -100,200 +86,49 @@ class DerivativesCppadJIT : public Derivatives // doub * @param inputDim input dimension, must be specified if template parameter IN_DIM is -1 (dynamic) * @param outputDim output dimension, must be specified if template parameter IN_DIM is -1 (dynamic) */ - void update(FUN_TYPE_CG& f, const size_t inputDim = IN_DIM, const size_t outputDim = OUT_DIM) - { - cgStdFun_ = f; - outputDim_ = outputDim; - inputDim_ = inputDim; - if (outputDim_ > 0 && inputDim_ > 0) - { - recordCg(); - compiled_ = false; - libName_ = ""; - dynamicLib_ = nullptr; - model_ = nullptr; - } - } - - //! destructor + void update(FUN_TYPE_CG& f, const size_t inputDim = IN_DIM, const size_t outputDim = OUT_DIM); + virtual ~DerivativesCppadJIT() = default; - //! deep cloning of Jacobian - DerivativesCppadJIT* clone() const { return new DerivativesCppadJIT(*this); } - virtual OUT_TYPE_D forwardZero(const Eigen::VectorXd& x) - { - if (compiled_) - { - assert(model_->isForwardZeroAvailable() == true); - return model_->ForwardZero(x); - } - else - { - throw std::runtime_error("Error: Compile the library first by calling compileJIT(..)"); - } - } - - virtual JAC_TYPE_D jacobian(const Eigen::VectorXd& x) - { - if (outputDim_ <= 0) - throw std::runtime_error("Outdim dim smaller 0; Define output dim in DerivativesCppad constructor"); - - - Eigen::VectorXd jac; - if (compiled_) - { - assert(model_->isJacobianAvailable() == true); - jac = model_->Jacobian(x); - JAC_TYPE_D out(outputDim_, x.rows()); - out = JAC_TYPE_ROW_MAJOR::Map(jac.data(), outputDim_, x.rows()); - return out; - } - else - throw std::runtime_error("Error: Compile the library first by calling compileJIT(..)"); - } + + //! deep cloning + DerivativesCppadJIT* clone() const; + + virtual OUT_TYPE_D forwardZero(const Eigen::VectorXd& x); + + virtual JAC_TYPE_D jacobian(const Eigen::VectorXd& x); virtual void sparseJacobian(const Eigen::VectorXd& x, Eigen::VectorXd& jac, Eigen::VectorXi& iRow, - Eigen::VectorXi& jCol) - { - if (outputDim_ <= 0) - throw std::runtime_error("Outdim dim smaller 0; Define output dim in DerivativesCppad constructor"); - - if (compiled_) - { - assert(model_->isSparseJacobianAvailable() == true); - std::vector input(x.data(), x.data() + x.rows() * x.cols()); - std::vector output; - model_->SparseJacobian(input, output, sparsityRowsJacobian_, sparsityColsJacobian_); - jac = Eigen::Map(output.data(), output.size(), 1); - iRow = sparsityRowsJacobianEigen_; - jCol = sparsityColsJacobianEigen_; - } - else - throw std::runtime_error("Error: Compile the library first by calling compileJIT(..)"); - } - - virtual Eigen::VectorXd sparseJacobianValues(const Eigen::VectorXd& x) - { - if (outputDim_ <= 0) - throw std::runtime_error("Outdim dim smaller 0; Define output dim in DerivativesCppad constructor"); - - if (compiled_) - { - assert(model_->isSparseJacobianAvailable() == true); - std::vector input(x.data(), x.data() + x.rows() * x.cols()); - std::vector output; - model_->SparseJacobian(input, output, sparsityRowsJacobian_, sparsityColsJacobian_); - return Eigen::Map(output.data(), output.size(), 1); - } - else - throw std::runtime_error("Error: Compile the library first by calling compileJIT(..)"); - } - - - virtual HES_TYPE_D hessian(const Eigen::VectorXd& x, const Eigen::VectorXd& lambda) - { - if (outputDim_ <= 0) - throw std::runtime_error("Outdim dim smaller 0; Define output dim in DerivativesCppad constructor"); - - if (compiled_) - { - assert(model_->isHessianAvailable() == true); - Eigen::VectorXd hessian = model_->Hessian(x, lambda); - HES_TYPE_D out(x.rows(), x.rows()); - out = HES_TYPE_ROW_MAJOR::Map(hessian.data(), x.rows(), x.rows()); - return out; - } - else - { - throw std::runtime_error("Error: Compile the library first by calling compileJIT(..)"); - } - } + Eigen::VectorXi& jCol); + + virtual Eigen::VectorXd sparseJacobianValues(const Eigen::VectorXd& x); + + + virtual HES_TYPE_D hessian(const Eigen::VectorXd& x, const Eigen::VectorXd& lambda); virtual void sparseHessian(const Eigen::VectorXd& x, const Eigen::VectorXd& lambda, Eigen::VectorXd& hes, Eigen::VectorXi& iRow, - Eigen::VectorXi& jCol) - { - if (outputDim_ <= 0) - throw std::runtime_error("Outdim dim smaller 0; Define output dim in DerivativesCppad constructor"); - - if (compiled_) - { - assert(model_->isSparseJacobianAvailable() == true); - std::vector input(x.data(), x.data() + x.rows() * x.cols()); - std::vector inputLambda(lambda.data(), lambda.data() + lambda.rows() * lambda.cols()); - std::vector output; - model_->SparseHessian(input, inputLambda, output, sparsityRowsHessian_, sparsityColsHessian_); - hes = Eigen::Map(output.data(), output.size(), 1); - iRow = sparsityRowsHessianEigen_; - jCol = sparsityColsHessianEigen_; - } - else - throw std::runtime_error("Error: Compile the library first by calling compileJIT(..)"); - } - - - virtual Eigen::VectorXd sparseHessianValues(const Eigen::VectorXd& x, const Eigen::VectorXd& lambda) - { - if (outputDim_ <= 0) - throw std::runtime_error("Outdim dim smaller 0; Define output dim in DerivativesCppad constructor"); - - if (compiled_) - { - assert(model_->isSparseHessianAvailable() == true); - std::vector input(x.data(), x.data() + x.rows() * x.cols()); - std::vector inputLambda(lambda.data(), lambda.data() + lambda.rows() * lambda.cols()); - std::vector output; - model_->SparseHessian(input, inputLambda, output, sparsityRowsHessian_, sparsityColsHessian_); - return Eigen::Map(output.data(), output.size(), 1); - } - else - throw std::runtime_error("Error: Compile the library first by calling compileJIT(..)"); - } + Eigen::VectorXi& jCol); + + + virtual Eigen::VectorXd sparseHessianValues(const Eigen::VectorXd& x, const Eigen::VectorXd& lambda); //! get Jacobian sparsity pattern /*! * Auto-Diff automatically detects the sparsity pattern of the Jacobian. This method returns the pattern. * @return Sparsity pattern of the Jacobian */ - Eigen::Matrix getSparsityPatternJacobian() - { - assert(model_->isJacobianSparsityAvailable() == true); - - std::vector sparsityVec = model_->JacobianSparsityBool(); - Eigen::Matrix sparsityMat(outputDim_, inputDim_); - - assert((int)(sparsityVec.size()) == outputDim_ * inputDim_); - for (int row = 0; row < outputDim_; ++row) - for (int col = 0; col < inputDim_; ++col) - sparsityMat(row, col) = sparsityVec[col + row * inputDim_]; - - return sparsityMat; - } + Eigen::Matrix getSparsityPatternJacobian(); /** * @brief get Hessian sparsity pattern * * @return Auto-diff automatically detects the sparsity pattern of the Hessian */ - Eigen::Matrix getSparsityPatternHessian() - { - assert(model_->isHessianSparsityAvailable() == true); - - std::vector sparsityVec = model_->HessianSparsityBool(); - Eigen::Matrix sparsityMat(inputDim_, inputDim_); - - assert(sparsityVec.size() == inputDim_ * inputDim_); - for (int row = 0; row < inputDim_; ++row) - for (int col = 0; col < inputDim_; ++col) - { - sparsityMat(row, col) = sparsityVec[col + row * inputDim_]; - } - - return sparsityMat; - } + Eigen::Matrix getSparsityPatternHessian(); //! get Jacobian sparsity pattern @@ -304,35 +139,21 @@ class DerivativesCppadJIT : public Derivatives // doub * @param rows row indeces of non-zero entries * @param columns column indeces of non-zero entries */ - void getSparsityPatternJacobian(Eigen::VectorXi& rows, Eigen::VectorXi& columns) - { - assert(model_->isJacobianSparsityAvailable() == true); - - rows = sparsityRowsJacobianEigen_; - columns = sparsityColsJacobianEigen_; - } + void getSparsityPatternJacobian(Eigen::VectorXi& rows, Eigen::VectorXi& columns); /** * @brief Returns the number of nonzeros in the sparse jacobian * * @return The number of nonzeros in the sparse jacobian */ - size_t getNumNonZerosJacobian() - { - assert(model_->isJacobianSparsityAvailable() == true); - return sparsityRowsJacobian_.size(); - } + size_t getNumNonZerosJacobian(); /** * @brief Returns the number of nonzeros in the sparse hessian * * @return The number of non zeros in the sparse hessian */ - size_t getNumNonZerosHessian() - { - assert(model_->isJacobianSparsityAvailable() == true); - return sparsityRowsHessian_.size(); - } + size_t getNumNonZerosHessian(); //! get Hessian sparsity pattern /*! @@ -342,13 +163,7 @@ class DerivativesCppadJIT : public Derivatives // doub * @param rows row indeces of non-zero entries * @param columns column indeces of non-zero entries */ - void getSparsityPatternHessian(Eigen::VectorXi& rows, Eigen::VectorXi& columns) - { - assert(model_->isHessianSparsityAvailable() == true); - - rows = sparsityRowsHessianEigen_; - columns = sparsityColsHessianEigen_; - } + void getSparsityPatternHessian(Eigen::VectorXi& rows, Eigen::VectorXi& columns); //! Uses just-in-time compilation to compile the Jacobian and other derivatives @@ -358,134 +173,19 @@ class DerivativesCppadJIT : public Derivatives // doub */ void compileJIT(const DerivativesCppadSettings& settings, const std::string& libName = "unnamedLib", - bool verbose = false) - { - if (compiled_) - return; - - struct timespec ts; - clock_gettime(CLOCK_MONOTONIC, &ts); - - // assigning a unique identifier to the library in order to avoid race conditions in JIT - std::string uniqueID = - std::to_string(std::hash()(std::this_thread::get_id())) + "_" + std::to_string(ts.tv_nsec); - - libName_ = libName + uniqueID; - - CppAD::cg::ModelCSourceGen cgen(cgCppadFun_, "DerivativesCppad" + libName_); - - cgen.setMultiThreading(settings.multiThreading_); - cgen.setCreateForwardZero(settings.createForwardZero_); - cgen.setCreateForwardOne(settings.createForwardOne_); - cgen.setCreateReverseOne(settings.createReverseOne_); - cgen.setCreateReverseTwo(settings.createReverseTwo_); - cgen.setCreateJacobian(settings.createJacobian_); - cgen.setCreateSparseJacobian(settings.createSparseJacobian_); - cgen.setCreateHessian(settings.createHessian_); - cgen.setCreateSparseHessian(settings.createSparseHessian_); - cgen.setMaxAssignmentsPerFunc(settings.maxAssignements_); - - CppAD::cg::ModelLibraryCSourceGen libcgen(cgen); - std::string tempDir = "cppad_temp" + uniqueID; - if (verbose) - { - std::cout << "DerivativesCppadJIT: starting to compile " << libName_ << " library ..." << std::endl; - std::cout << "DerivativesCppadJIT: in temporary directory " << tempDir << std::endl; - } - - // compile source code - CppAD::cg::DynamicModelLibraryProcessor p(libcgen, libName_); - if (settings.compiler_ == DerivativesCppadSettings::GCC) - { - CppAD::cg::GccCompiler compiler; - compiler.setTemporaryFolder(tempDir); - dynamicLib_ = std::shared_ptr>(p.createDynamicLibrary(compiler)); - } - else if (settings.compiler_ == DerivativesCppadSettings::CLANG) - { - CppAD::cg::ClangCompiler compiler; - compiler.setTemporaryFolder(tempDir); - dynamicLib_ = std::shared_ptr>(p.createDynamicLibrary(compiler)); - } - - if (settings.generateSourceCode_) - { - CppAD::cg::SaveFilesModelLibraryProcessor p2(libcgen); - p2.saveSources(); - } - - model_ = std::shared_ptr>(dynamicLib_->model("DerivativesCppad" + libName_)); - - compiled_ = true; - - if (verbose) - std::cout << "DerivativesCppadJIT: successfully compiled " << libName_ << std::endl; - - if (model_->isJacobianSparsityAvailable()) - { - model_->JacobianSparsity(sparsityRowsJacobian_, sparsityColsJacobian_); - sparsityRowsJacobianEigen_.resize(sparsityRowsJacobian_.size()); //rowsTmp.resize(rowsVec.size()); - sparsityColsJacobianEigen_.resize(sparsityColsJacobian_.size()); //colsTmp.resize(rowsVec.size()); - - Eigen::Matrix rowsSizeT; - rowsSizeT.resize(sparsityRowsJacobian_.size()); - Eigen::Matrix colsSizeT; - colsSizeT.resize(sparsityColsJacobian_.size()); - - rowsSizeT = Eigen::Map>( - sparsityRowsJacobian_.data(), sparsityRowsJacobian_.size(), 1); - colsSizeT = Eigen::Map>( - sparsityColsJacobian_.data(), sparsityColsJacobian_.size(), 1); - - sparsityRowsJacobianEigen_ = rowsSizeT.cast(); - sparsityColsJacobianEigen_ = colsSizeT.cast(); - } - - if (model_->isHessianSparsityAvailable()) - { - model_->HessianSparsity(sparsityRowsHessian_, sparsityColsHessian_); - sparsityRowsHessianEigen_.resize(sparsityRowsHessian_.size()); //rowsTmp.resize(rowsVec.size()); - sparsityColsHessianEigen_.resize(sparsityColsHessian_.size()); //colsTmp.resize(rowsVec.size()); - - Eigen::Matrix rowsSizeT; - rowsSizeT.resize(sparsityRowsHessian_.size()); - Eigen::Matrix colsSizeT; - colsSizeT.resize(sparsityColsHessian_.size()); - - rowsSizeT = Eigen::Map>( - sparsityRowsHessian_.data(), sparsityRowsHessian_.size(), 1); - colsSizeT = Eigen::Map>( - sparsityColsHessian_.data(), sparsityColsHessian_.size(), 1); - - sparsityRowsHessianEigen_ = rowsSizeT.cast(); - sparsityColsHessianEigen_ = colsSizeT.cast(); - } - } + bool verbose = false); //! retrieve the dynamic library, e.g. for testing purposes - const std::shared_ptr> getDynamicLib() { return dynamicLib_; } -protected: - //! record the Auto-Diff terms for code generation - void recordCg() - { - // input vector, needs to be dynamic size - Eigen::Matrix x(inputDim_); - - // declare x as independent - CppAD::Independent(x); - - // output vector, needs to be dynamic size - Eigen::Matrix y(outputDim_); + const std::shared_ptr> getDynamicLib(); - y = cgStdFun_(x); +#ifdef LLVM_VERSION_MAJOR + //! retrieve the llvm in-memory library, e.g. for testing purposes + const std::shared_ptr> getLlvmLib(); +#endif - // store operation sequence in f: x -> y and stop recording - CppAD::ADFun fCodeGen(x, y); - - fCodeGen.optimize(); - - cgCppadFun_ = fCodeGen; - } +protected: + //! record the Auto-Diff terms for code generation + void recordCg(); std::function cgStdFun_; //! the function @@ -509,9 +209,17 @@ class DerivativesCppadJIT : public Derivatives // doub //! CppAD::cg::GccCompiler compiler_; //! compile for codegeneration CppAD::cg::ClangCompiler compilerClang_; - std::shared_ptr> dynamicLib_; //! dynamic library to load after compilation - std::shared_ptr> model_; //! the model + std::shared_ptr> dynamicLib_; //! dynamic library to load after compilation + std::shared_ptr> model_; //! the model +#ifdef LLVM_VERSION_MAJOR + std::shared_ptr> llvmModelLib_; //! llvm in-memory library +#endif }; + } /* namespace core */ } /* namespace ct */ + +#endif + +#include "DerivativesCppadJIT-impl.h" diff --git a/ct_core/include/ct/core/math/DerivativesCppadSettings.h b/ct_core/include/ct/core/math/DerivativesCppadSettings.h index e8b35e97a..180d59b3d 100644 --- a/ct_core/include/ct/core/math/DerivativesCppadSettings.h +++ b/ct_core/include/ct/core/math/DerivativesCppadSettings.h @@ -13,6 +13,7 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) namespace ct { namespace core { + /** * @ingroup NLP * @@ -23,7 +24,12 @@ class DerivativesCppadSettings public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW - typedef enum CompilerType { GCC = 0, CLANG = 1, num_types_compiler } Compiler_t; + typedef enum CompilerType + { + GCC = 0, + CLANG = 1, + num_types_compiler + } Compiler_t; /** * @brief Default constructor, set default settings @@ -40,7 +46,8 @@ class DerivativesCppadSettings createSparseHessian_(false), maxAssignements_(20000), compiler_(GCC), - generateSourceCode_(false) + generateSourceCode_(false), + useDynamicLibrary_(true) { } @@ -56,6 +63,8 @@ class DerivativesCppadSettings size_t maxAssignements_; CompilerType compiler_; bool generateSourceCode_; + bool useDynamicLibrary_; + /** * @brief Prints out settings */ @@ -88,6 +97,9 @@ class DerivativesCppadSettings if (generateSourceCode_) std::cout << "Generating and saving Source Code" << std::endl; + + if (useDynamicLibrary_) + std::cout << "Creating a dynamic library (*.so will be saved in execution directory)" << std::endl; } /** @@ -96,6 +108,7 @@ class DerivativesCppadSettings * @return Returns true of the parameters are ok */ bool parametersOk() const { return true; } + /** * @brief Loads the settings from a .info file * @@ -119,6 +132,7 @@ class DerivativesCppadSettings createSparseHessian_ = pt.get(ns + ".CreateSparseHessian"); maxAssignements_ = pt.get(ns + ".MaxAssignements"); generateSourceCode_ = pt.get(ns + ".GenerateSourceCode"); + useDynamicLibrary_ = pt.get(ns + ".UseDynamicLibrary"); std::string compilerStr = pt.get(ns + ".Compiler"); diff --git a/ct_core/include/ct/core/systems/continuous_time/linear/ADCodegenLinearizer.h b/ct_core/include/ct/core/systems/continuous_time/linear/ADCodegenLinearizer.h index 98f279f0c..e4c1d8fa0 100644 --- a/ct_core/include/ct/core/systems/continuous_time/linear/ADCodegenLinearizer.h +++ b/ct_core/include/ct/core/systems/continuous_time/linear/ADCodegenLinearizer.h @@ -6,6 +6,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #include +#ifdef CPPADCG + namespace ct { namespace core { @@ -271,3 +273,5 @@ class ADCodegenLinearizer : public LinearSystem } // namespace core } // namespace ct + +#endif \ No newline at end of file diff --git a/ct_core/include/ct/core/systems/continuous_time/linear/AutoDiffLinearizer.h b/ct_core/include/ct/core/systems/continuous_time/linear/AutoDiffLinearizer.h index f1dff9bf1..729358b86 100644 --- a/ct_core/include/ct/core/systems/continuous_time/linear/AutoDiffLinearizer.h +++ b/ct_core/include/ct/core/systems/continuous_time/linear/AutoDiffLinearizer.h @@ -5,6 +5,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once +#ifdef CPPAD + namespace ct { namespace core { @@ -159,3 +161,5 @@ class AutoDiffLinearizer : public LinearSystem } // namespace core } // namespace ct + +#endif \ No newline at end of file diff --git a/ct_core/include/ct/core/systems/continuous_time/linear/LTISystem.h b/ct_core/include/ct/core/systems/continuous_time/linear/LTISystem.h index e14251f95..f26251848 100644 --- a/ct_core/include/ct/core/systems/continuous_time/linear/LTISystem.h +++ b/ct_core/include/ct/core/systems/continuous_time/linear/LTISystem.h @@ -5,6 +5,10 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-value" + namespace ct { namespace core { @@ -182,5 +186,8 @@ class LTISystem : public LinearSystem Eigen::Matrix C_; //!< C matrix Eigen::Matrix D_; //!< D matrix }; -} -} + +} // namespace core +} // namespace ct + +#pragma GCC diagnostic pop \ No newline at end of file diff --git a/ct_core/include/ct/core/systems/discrete_time/SwitchedDiscreteControlledSystem.h b/ct_core/include/ct/core/systems/discrete_time/SwitchedDiscreteControlledSystem.h index 018525bc9..0c56b60f5 100644 --- a/ct_core/include/ct/core/systems/discrete_time/SwitchedDiscreteControlledSystem.h +++ b/ct_core/include/ct/core/systems/discrete_time/SwitchedDiscreteControlledSystem.h @@ -97,7 +97,7 @@ class SwitchedDiscreteControlledSystem : public DiscreteControlledSystem* clone() const + virtual SwitchedDiscreteControlledSystem* clone() const override { return new SwitchedDiscreteControlledSystem(*this); }; diff --git a/ct_core/include/ct/core/systems/discrete_time/linear/DiscreteSystemLinearizerAD.h b/ct_core/include/ct/core/systems/discrete_time/linear/DiscreteSystemLinearizerAD.h index 384ae4b44..5d75d4705 100644 --- a/ct_core/include/ct/core/systems/discrete_time/linear/DiscreteSystemLinearizerAD.h +++ b/ct_core/include/ct/core/systems/discrete_time/linear/DiscreteSystemLinearizerAD.h @@ -4,6 +4,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) **********************************************************************************************************************/ #pragma once +#ifdef CPPAD + namespace ct { namespace core { @@ -187,3 +189,5 @@ class DiscreteSystemLinearizerAD : public DiscreteLinearSystem namespace ct { @@ -76,8 +78,8 @@ class DynamicsLinearizerADBase return "float"; } - //! destructor - virtual ~DynamicsLinearizerADBase() {} + virtual ~DynamicsLinearizerADBase() = default; + protected: const size_t A_entries = STATE_DIM * STATE_DIM; //!< number of entries in the state Jacobian const size_t B_entries = STATE_DIM * CONTROL_DIM; //!< number of entries in the input Jacobian @@ -162,3 +164,5 @@ class DynamicsLinearizerADBase } // namespace internal } // namespace core } // namespace ct + +#endif \ No newline at end of file diff --git a/ct_core/include/ct/core/systems/linearizer/DynamicsLinearizerADCG.h b/ct_core/include/ct/core/systems/linearizer/DynamicsLinearizerADCG.h index 673d3714f..37ed01421 100644 --- a/ct_core/include/ct/core/systems/linearizer/DynamicsLinearizerADCG.h +++ b/ct_core/include/ct/core/systems/linearizer/DynamicsLinearizerADCG.h @@ -4,6 +4,9 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) **********************************************************************************************************************/ #pragma once +#ifdef CPPADCG +#ifdef CPPAD + #include "DynamicsLinearizerADBase.h" #include @@ -263,3 +266,6 @@ class DynamicsLinearizerADCG : public internal::DynamicsLinearizerADBase Requirements for a CppAD Base Type$$ - -$head Syntax$$ -$code # include $$ - -$head Purpose$$ -This section lists the requirements for the type -$icode Base$$ so that the type $codei%AD<%Base%>%$$ can be used. - -$head API Warning$$ -Defining a CppAD $icode Base$$ type is an advanced use of CppAD. -This part of the CppAD API changes with time. The most common change -is adding more requirements. -Search for $code base_require$$ in the -current $cref whats_new$$ section for these changes. - -$head Standard Base Types$$ -In the case where $icode Base$$ is -$code float$$, -$code double$$, -$code std::complex$$, -$code std::complex$$, -or $codei%AD<%Other%>%$$, -these requirements are provided by including the file -$code cppad/cppad.hpp$$. - -$head Include Order$$ -If you are linking a non-standard base type to CppAD, -you must first include the file $code cppad/base_require.hpp$$, -then provide the specifications below, -and then include the file $code cppad/cppad.hpp$$. - -$head Numeric Type$$ -The type $icode Base$$ must support all the operations for a -$cref NumericType$$. - -$head Output Operator$$ -The type $icode Base$$ must support the syntax -$codei% - %os% << %x% -%$$ -where $icode os$$ is an $code std::ostream&$$ -and $icode x$$ is a $code const base_alloc&$$. -For example, see -$cref/base_alloc/base_alloc.hpp/Output Operator/$$. - -$head Integer$$ -The type $icode Base$$ must support the syntax -$codei% - %i% = CppAD::Integer(%x%) -%$$ -which converts $icode x$$ to an $code int$$. -The argument $icode x$$ has prototype -$codei% - const %Base%& %x% -%$$ -and the return value $icode i$$ has prototype -$codei% - int %i% -%$$ - -$subhead Suggestion$$ -In many cases, the $icode Base$$ version of the $code Integer$$ function -can be defined by -$codei% -namespace CppAD { - inline int Integer(const %Base%& x) - { return static_cast(x); } -} -%$$ -For example, see -$cref/base_float/base_float.hpp/Integer/$$ and -$cref/base_alloc/base_alloc.hpp/Integer/$$. - -$head Absolute Zero, azmul$$ -The type $icode Base$$ must support the syntax -$codei% - %z% = azmul(%x%, %y%) -%$$ -see; $cref azmul$$. -The following preprocessor macro invocation suffices -(for most $icode Base$$ types): -$codei% -namespace CppAD { - CPPAD_AZMUL(%Base%) -} -%$$ -where the macro is defined by -$codep */ -# define CPPAD_AZMUL(Base) \ - inline Base azmul(const Base& x, const Base& y) \ - { Base zero(0.0); \ - if( x == zero ) \ - return zero; \ - return x * y; \ - } -/* $$ - -$childtable% - omh/base_require/base_member.omh% - cppad/local/base_cond_exp.hpp% - omh/base_require/base_identical.omh% - omh/base_require/base_ordered.omh% - cppad/local/base_std_math.hpp% - cppad/local/base_limits.hpp% - cppad/local/base_to_string.hpp% - omh/base_require/base_example.omh -%$$ - -$end -*/ - -// definitions that must come before base implementations -# include -# include -# include -# include - -// grouping documentation by feature -# include -# include -# include -# include - -// must define template class numeric_limits before the base cases -# include -# include // deprecated - -// base cases that come with CppAD -# include -# include -# include - -// deprecated base type -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/cg.hpp b/ct_core/include/ct/external/cppad/cg.hpp deleted file mode 100644 index 260545e31..000000000 --- a/ct_core/include/ct/external/cppad/cg.hpp +++ /dev/null @@ -1,20 +0,0 @@ -#ifndef CPPAD_CG_INCLUDED -#define CPPAD_CG_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2015 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/AUTHORS b/ct_core/include/ct/external/cppad/cg/AUTHORS deleted file mode 100644 index e24497f36..000000000 --- a/ct_core/include/ct/external/cppad/cg/AUTHORS +++ /dev/null @@ -1,8 +0,0 @@ - Statement of CppADCodeGen Authorship and Copyright - ================================================== - -CppADCodeGen source is developed by Joao Rui Leal. -CppAD source code is developed by Bradley M. Bell. - -CppADCodeGen copyright holder is Ciengis, SA, while the original CppAD -library copyright holder is Bradley M. Bell. \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/COPYING b/ct_core/include/ct/external/cppad/cg/COPYING deleted file mode 100644 index f93b4cf5f..000000000 --- a/ct_core/include/ct/external/cppad/cg/COPYING +++ /dev/null @@ -1,10 +0,0 @@ -CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - Copyright (C) 2012 Ciengis - -CppADCodeGen is distributed under multiple licenses: - - - Eclipse Public License Version 1.0 (EPL1), and - - GNU General Public License Version 3 (GPL3). - -EPL1 terms and conditions can be found in the file epl-v10.txt, while -terms and conditions for the GPL3 can be found in the file gpl3.txt. \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/abstract_atomic_fun.hpp b/ct_core/include/ct/external/cppad/cg/abstract_atomic_fun.hpp deleted file mode 100644 index c24036826..000000000 --- a/ct_core/include/ct/external/cppad/cg/abstract_atomic_fun.hpp +++ /dev/null @@ -1,466 +0,0 @@ -#ifndef CPPAD_CG_ABSTRACT_ATOMIC_FUN_INCLUDED -#define CPPAD_CG_ABSTRACT_ATOMIC_FUN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * An atomic function for source code generation - * - * @author Joao Leal - */ -template -class CGAbstractAtomicFun : public BaseAbstractAtomicFun { -public: - typedef CppAD::cg::CG CGB; - typedef Argument Arg; -protected: - const size_t id_; - bool standAlone_; - -protected: - - /** - * Creates a new atomic function that is responsible for defining the - * dependencies to calls of a user atomic function. - * - * @param name The atomic function name. - * @param standAlone Whether or not forward and reverse function calls - * do not require the Taylor coefficients for the - * dependent variables (ty) and any previous - * evaluation of other forward/reverse modes. - */ - CGAbstractAtomicFun(const std::string& name, bool standAlone = false) : - BaseAbstractAtomicFun(name), - id_(createNewId()), - standAlone_(standAlone) { - CPPADCG_ASSERT_KNOWN(!name.empty(), "The atomic function name cannot be empty"); - this->option(CppAD::atomic_base::set_sparsity_enum); - } - -public: - - template - void operator()(const ADVector& ax, ADVector& ay, size_t id = 0) { - this->BaseAbstractAtomicFun::operator()(ax, ay, id); - } - - /** - * Provides a unique identifier for this atomic function type. - * - * @return a unique identifier ID - */ - size_t getId() const { - return id_; - } - - virtual bool forward(size_t q, - size_t p, - const CppAD::vector& vx, - CppAD::vector& vy, - const CppAD::vector& tx, - CppAD::vector& ty) override { - using CppAD::vector; - - bool valuesDefined = BaseAbstractAtomicFun::isValuesDefined(tx); - if (vx.size() > 0) - zeroOrderDependency(vx, vy); - - bool allParameters = BaseAbstractAtomicFun::isParameters(tx); - if (allParameters) { - vector tyb; - if (!evalForwardValues(q, p, tx, tyb, ty.size())) - return false; - - CPPADCG_ASSERT_UNKNOWN(tyb.size() == ty.size()); - for (size_t i = 0; i < ty.size(); i++) { - ty[i] = tyb[i]; - } - return true; - } - - size_t m = ty.size() / (p + 1); - - vector vyLocal; - if (p == 0) { - vyLocal = vy; - } else if (p >= 1) { - /** - * Use the jacobian sparsity to determine which elements - * will always be zero - */ - - size_t n = tx.size() / (p + 1); - - vector > r(n); - for (size_t j = 0; j < n; j++) { - if (!tx[j * (p + 1) + 1].isIdenticalZero()) - r[j].insert(0); - } - vector > s(m); - this->for_sparse_jac(1, r, s); - - vyLocal.resize(ty.size()); - for (size_t i = 0; i < vyLocal.size(); i++) { - vyLocal[i] = true; - } - - for (size_t i = 0; i < m; i++) { - vyLocal[i * (p + 1) + 1] = s[i].size() > 0; - } - - if (p == 1) { - bool allZero = true; - for (size_t i = 0; i < vyLocal.size(); i++) { - if (vyLocal[i]) { - allZero = false; - break; - } - } - - if (allZero) { - for (size_t i = 0; i < ty.size(); i++) { - ty[i] = Base(0.0); - } - return true; - } - } - } - - vector tyb; - if (valuesDefined) { - if (!evalForwardValues(q, p, tx, tyb, ty.size())) - return false; - } - - CodeHandler* handler = findHandler(tx); - CPPADCG_ASSERT_UNKNOWN(handler != nullptr); - - size_t p1 = p + 1; - - std::vector*> txArray(p1), tyArray(p1); - for (size_t k = 0; k < p1; k++) { - if (k == 0) - txArray[k] = BaseAbstractAtomicFun::makeArray(*handler, tx, p, k); - else - txArray[k] = BaseAbstractAtomicFun::makeSparseArray(*handler, tx, p, k); - tyArray[k] = BaseAbstractAtomicFun::makeZeroArray(*handler, m); - } - - std::vector > args(2 * p1); - for (size_t k = 0; k < p1; k++) { - args[0 * p1 + k] = *txArray[k]; - args[1 * p1 + k] = *tyArray[k]; - } - - OperationNode* atomicOp = handler->makeNode(CGOpCode::AtomicForward,{id_, q, p}, args); - handler->registerAtomicFunction(*this); - - for (size_t k = 0; k < p1; k++) { - for (size_t i = 0; i < m; i++) { - size_t pos = i * p1 + k; - if (vyLocal.size() == 0 || vyLocal[pos]) { - ty[pos] = CGB(*handler->makeNode(CGOpCode::ArrayElement, {i}, {*tyArray[k], *atomicOp})); - if (valuesDefined) { - ty[pos].setValue(tyb[pos]); - } - } else { - CPPADCG_ASSERT_KNOWN(tyb.size() == 0 || IdenticalZero(tyb[pos]), "Invalid value"); - ty[pos] = 0; // not a variable (zero) - } - } - } - - return true; - } - - virtual bool reverse(size_t p, - const CppAD::vector& tx, - const CppAD::vector& ty, - CppAD::vector& px, - const CppAD::vector& py) override { - using CppAD::vector; - - bool allParameters = BaseAbstractAtomicFun::isParameters(tx); - if (allParameters) { - allParameters = BaseAbstractAtomicFun::isParameters(ty); - if (allParameters) { - allParameters = BaseAbstractAtomicFun::isParameters(py); - } - } - - if (allParameters) { - vector pxb; - - if (!evalReverseValues(p, tx, ty, pxb, py)) - return false; - - CPPADCG_ASSERT_UNKNOWN(pxb.size() == px.size()); - - for (size_t i = 0; i < px.size(); i++) { - px[i] = pxb[i]; - } - return true; - } - - /** - * Use the Jacobian sparsity to determine which elements - * will always be zero - */ - vector vxLocal(px.size()); - for (size_t j = 0; j < vxLocal.size(); j++) { - vxLocal[j] = true; - } - - size_t p1 = p + 1; - // k == 0 - size_t m = ty.size() / p1; - size_t n = tx.size() / p1; - - vector< std::set > rt(m); - for (size_t i = 0; i < m; i++) { - if (!py[i * p1].isIdenticalZero()) { - rt[i].insert(0); - } - } - vector< std::set > st(n); - this->rev_sparse_jac(1, rt, st); - - for (size_t j = 0; j < n; j++) { - vxLocal[j * p1 + p] = st[j].size() > 0; - } - - if (p >= 1) { - /** - * Use the Hessian sparsity to determine which elements - * will always be zero - */ - vector vx(n); - vector s(m); - vector t(n); - vector< std::set > r(n); - vector< std::set > u(m); - vector< std::set > v(n); - - for (size_t j = 0; j < n; j++) { - vx[j] = !tx[j * p1].isParameter(); - if (!tx[j * p1 + 1].isIdenticalZero()) { - r[j].insert(0); - } - } - for (size_t i = 0; i < m; i++) { - s[i] = !py[i * p1 + 1].isIdenticalZero(); - } - - this->rev_sparse_hes(vx, s, t, 1, r, u, v); - - for (size_t j = 0; j < n; j++) { - vxLocal[j * p1 + p - 1] = v[j].size() > 0; - } - } - - bool allZero = true; - for (size_t j = 0; j < vxLocal.size(); j++) { - if (vxLocal[j]) { - allZero = false; - break; - } - } - - if (allZero) { - for (size_t j = 0; j < px.size(); j++) { - px[j] = Base(0.0); - } - return true; - } - - bool valuesDefined = BaseAbstractAtomicFun::isValuesDefined(tx); - if (valuesDefined) { - valuesDefined = BaseAbstractAtomicFun::isValuesDefined(ty); - if (valuesDefined) { - valuesDefined = BaseAbstractAtomicFun::isValuesDefined(py); - } - } - - vector pxb; - if (valuesDefined) { - if (!evalReverseValues(p, tx, ty, pxb, py)) - return false; - } - - CodeHandler* handler = findHandler(tx); - if (handler == nullptr) { - handler = findHandler(ty); - if (handler == nullptr) { - handler = findHandler(py); - } - } - CPPADCG_ASSERT_UNKNOWN(handler != nullptr); - - std::vector*> txArray(p1), tyArray(p1), pxArray(p1), pyArray(p1); - for (size_t k = 0; k <= p; k++) { - if (k == 0) - txArray[k] = BaseAbstractAtomicFun::makeArray(*handler, tx, p, k); - else - txArray[k] = BaseAbstractAtomicFun::makeSparseArray(*handler, tx, p, k); - - if (standAlone_) { - tyArray[k] = BaseAbstractAtomicFun::makeEmptySparseArray(*handler, m); - } else { - tyArray[k] = BaseAbstractAtomicFun::makeSparseArray(*handler, ty, p, k); - } - - if (k == 0) - pxArray[k] = BaseAbstractAtomicFun::makeZeroArray(*handler, n); - else - pxArray[k] = BaseAbstractAtomicFun::makeEmptySparseArray(*handler, n); - - if (k == 0) - pyArray[k] = BaseAbstractAtomicFun::makeSparseArray(*handler, py, p, k); - else - pyArray[k] = BaseAbstractAtomicFun::makeArray(*handler, py, p, k); - } - - std::vector > args(4 * p1); - for (size_t k = 0; k <= p; k++) { - args[0 * p1 + k] = *txArray[k]; - args[1 * p1 + k] = *tyArray[k]; - args[2 * p1 + k] = *pxArray[k]; - args[3 * p1 + k] = *pyArray[k]; - } - - OperationNode* atomicOp = handler->makeNode(CGOpCode::AtomicReverse,{id_, p}, args); - handler->registerAtomicFunction(*this); - - for (size_t k = 0; k < p1; k++) { - for (size_t j = 0; j < n; j++) { - size_t pos = j * p1 + k; - if (vxLocal[pos]) { - px[pos] = CGB(*handler->makeNode(CGOpCode::ArrayElement,{j}, {*pxArray[k], *atomicOp})); - if (valuesDefined) { - px[pos].setValue(pxb[pos]); - } - } else { - // CPPADCG_ASSERT_KNOWN(pxb.size() == 0 || IdenticalZero(pxb[j]), "Invalid value"); - // pxb[j] might be non-zero but it is not required (it might have been used to determine other pxbs) - px[pos] = Base(0); // not a variable (zero) - } - } - } - - return true; - } - - virtual ~CGAbstractAtomicFun() { - } - -protected: - - virtual void zeroOrderDependency(const CppAD::vector& vx, - CppAD::vector& vy) = 0; - - /** - * Used to evaluate function values and forward mode function values and - * derivatives. - * - * @param q Lowest order for this forward mode calculation. - * @param p Highest order for this forward mode calculation. - * @param vx If size not zero, which components of \c x are variables - * @param vy If size not zero, which components of \c y are variables - * @param tx Taylor coefficients corresponding to \c x for this - * calculation - * @param ty Taylor coefficient corresponding to \c y for this - * calculation - * @return true on success, false otherwise - */ - virtual bool atomicForward(size_t q, - size_t p, - const CppAD::vector& tx, - CppAD::vector& ty) = 0; - /** - * Used to evaluate reverse mode function derivatives. - * - * @param p Highest order for this forward mode calculation. - * @param tx Taylor coefficients corresponding to \c x for this - * calculation - * @param ty Taylor coefficient corresponding to \c y for this - * calculation - * @param px Partials w.r.t. the \c x Taylor coefficients. - * @param py Partials w.r.t. the \c y Taylor coefficients - * @return true on success, false otherwise - */ - virtual bool atomicReverse(size_t p, - const CppAD::vector& tx, - const CppAD::vector& ty, - CppAD::vector& px, - const CppAD::vector& py) = 0; - -private: - - inline bool evalForwardValues(size_t q, - size_t p, - const CppAD::vector& tx, - CppAD::vector& tyb, - size_t ty_size) { - CppAD::vector txb(tx.size()); - tyb.resize(ty_size); - - for (size_t i = 0; i < txb.size(); i++) { - txb[i] = tx[i].getValue(); - } - - return atomicForward(q, p, txb, tyb); - } - - inline bool evalReverseValues(size_t p, - const CppAD::vector& tx, - const CppAD::vector& ty, - CppAD::vector& pxb, - const CppAD::vector& py) { - using CppAD::vector; - - vector txb(tx.size()); - vector tyb(ty.size()); - pxb.resize(tx.size()); - vector pyb(py.size()); - - for (size_t i = 0; i < txb.size(); i++) { - txb[i] = tx[i].getValue(); - } - for (size_t i = 0; i < tyb.size(); i++) { - tyb[i] = ty[i].getValue(); - } - for (size_t i = 0; i < pyb.size(); i++) { - pyb[i] = py[i].getValue(); - } - - return atomicReverse(p, txb, tyb, pxb, pyb); - } - - static size_t createNewId() { - CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static size_t count = 0; - count++; - return count; - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/argument.hpp b/ct_core/include/ct/external/cppad/cg/argument.hpp deleted file mode 100644 index fa42d5793..000000000 --- a/ct_core/include/ct/external/cppad/cg/argument.hpp +++ /dev/null @@ -1,92 +0,0 @@ -#ifndef CPPAD_CG_ARGUMENT_INCLUDED -#define CPPAD_CG_ARGUMENT_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -class OperationNode; - -/** - * An argument used by an operation which can be either a constant value - * or the result of another operation - * - * @author Joao Leal - */ -template -class Argument { -private: - OperationNode* operation_; - Base* parameter_; -public: - - inline Argument() : - operation_(nullptr), - parameter_(nullptr) { - } - - inline Argument(OperationNode& operation) : - operation_(&operation), - parameter_(nullptr) { - } - - inline Argument(const Base& parameter) : - operation_(nullptr), - parameter_(new Base(parameter)) { - } - - inline Argument(const Argument& orig) : - operation_(orig.operation_), - parameter_(orig.parameter_ != nullptr ? new Base(*orig.parameter_) : nullptr) { - } - - inline Argument& operator=(const Argument& rhs) { - if (&rhs == this) { - return *this; - } - if (rhs.operation_ != nullptr) { - operation_ = rhs.operation_; - delete parameter_; - parameter_ = nullptr; - } else { - operation_ = nullptr; - if (parameter_ != nullptr) { - *parameter_ = *rhs.parameter_; - } else { - parameter_ = new Base(*rhs.parameter_); - } - } - return *this; - } - - inline OperationNode* getOperation() const { - return operation_; - } - - inline Base* getParameter() const { - return parameter_; - } - - virtual ~Argument() { - delete parameter_; - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif diff --git a/ct_core/include/ct/external/cppad/cg/arithmetic.hpp b/ct_core/include/ct/external/cppad/cg/arithmetic.hpp deleted file mode 100644 index f74e8951e..000000000 --- a/ct_core/include/ct/external/cppad/cg/arithmetic.hpp +++ /dev/null @@ -1,235 +0,0 @@ -#ifndef CPPAD_CG_ARITHMETIC_INCLUDED -#define CPPAD_CG_ARITHMETIC_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -CodeHandler* getHandler(const CG& left, - const CG& right) { - - CPPADCG_ASSERT_UNKNOWN(!left.isParameter() || !right.isParameter()); - - CodeHandler* lh = left.getCodeHandler(); - CodeHandler* rh = right.getCodeHandler(); - - if (lh == nullptr) { - return rh; - } else if (rh == nullptr) { - return lh; - } else { - if (lh != rh) { - throw CGException("Attempting to use several source code generation handlers in the same source code generation"); - } - return lh; - } -} - -template -inline CG operator+(const CG& left, const CG& right) { - if (left.isParameter() && right.isParameter()) { - return CG (left.getValue() + right.getValue()); - - } else { - if (left.isParameter()) { - if (left.isIdenticalZero()) { - return right; - } - } else if (right.isParameter()) { - if (right.isIdenticalZero()) { - return left; - } - } - - CodeHandler* handler = getHandler(left, right); - - CG result(*handler->makeNode(CGOpCode::Add,{left.argument(), right.argument()})); - if (left.isValueDefined() && right.isValueDefined()) { - result.setValue(left.getValue() + right.getValue()); - } - return result; - } -} - -template -inline CG operator-(const CG& left, const CG& right) { - if (left.isParameter() && right.isParameter()) { - return CG (left.getValue() - right.getValue()); - - } else { - if (right.isParameter()) { - if (right.isIdenticalZero()) { - return left; - } - } - - CodeHandler* handler = getHandler(left, right); - - CG result(*handler->makeNode(CGOpCode::Sub,{left.argument(), right.argument()})); - if (left.isValueDefined() && right.isValueDefined()) { - result.setValue(left.getValue() - right.getValue()); - } - return result; - } -} - -template -inline CG operator*(const CG& left, const CG& right) { - if (left.isParameter() && right.isParameter()) { - return CG (left.getValue() * right.getValue()); - - } else { - if (left.isParameter()) { - if (left.isIdenticalZero()) { - return CG (Base(0.0)); // does not consider the possibility of right being infinity - } else if (left.isIdenticalOne()) { - return right; - } - } else if (right.isParameter()) { - if (right.isIdenticalZero()) { - return CG (Base(0.0)); // does not consider the possibility of left being infinity - } else if (right.isIdenticalOne()) { - return left; - } - } - - CodeHandler* handler = getHandler(left, right); - - CG result(*handler->makeNode(CGOpCode::Mul,{left.argument(), right.argument()})); - if (left.isValueDefined() && right.isValueDefined()) { - result.setValue(left.getValue() * right.getValue()); - } - return result; - } -} - -template -inline CG operator/(const CG& left, const CG& right) { - if (left.isParameter() && right.isParameter()) { - return CG (left.getValue() / right.getValue()); - - } else { - if (left.isParameter()) { - if (left.isIdenticalZero()) { - return CG (Base(0.0)); // does not consider the possibility of right being infinity or zero - } - } else if (right.isParameter()) { - if (right.isIdenticalOne()) { - return left; - } - } else if (left.getOperationNode() == right.getOperationNode()) { - return CG(Base(1.0)); // does not consider the possibility of left/right being infinity or zero - } - - CodeHandler* handler = getHandler(left, right); - - CG result(*handler->makeNode(CGOpCode::Div,{left.argument(), right.argument()})); - if (left.isValueDefined() && right.isValueDefined()) { - result.setValue(left.getValue() / right.getValue()); - } - return result; - } -} - -template -inline CG operator+(const Base& left, const CG& right) { - return CG(left) + right; -} - -template -inline CG operator+(const CG& left, const Base& right) { - return left + CG(right); -} - -template -inline CG operator-(const Base& left, const CG& right) { - return CG(left) - right; -} - -template -inline CG operator-(const CG& left, const Base& right) { - return left - CG(right); -} - -template -inline CG operator/(const Base& left, const CG& right) { - return CG(left) / right; -} - -template -inline CG operator/(const CG& left, const Base& right) { - return left / CG(right); -} - -template -inline CG operator*(const Base& left, const CG& right) { - return CG(left) * right; -} - -template -inline CG operator*(const CG& left, const Base& right) { - return left * CG(right); -} - -/******************************************************************************* - * Operations with other types - ******************************************************************************/ -template -inline CG operator+(const T& left, const CG& right) { - return CG(Base(left)) + right; -} - -template -inline CG operator+(const CG& left, const T& right) { - return left + CG(Base(right)); -} - -template -inline CG operator-(const T& left, const CG& right) { - return CG(Base(left)) - right; -} - -template -inline CG operator-(const CG& left, const T& right) { - return left - CG(Base(right)); -} - -template -inline CG operator/(const T& left, const CG& right) { - return CG(Base(left)) / right; -} - -template -inline CG operator/(const CG& left, const T& right) { - return left / CG(Base(right)); -} - -template -inline CG operator*(const T& left, const CG& right) { - return CG(Base(left)) * right; -} - -template -inline CG operator*(const CG& left, const T& right) { - return left * CG(Base(right)); -} - -} // END cg namespace -} // END CppAD namespace - -#endif - diff --git a/ct_core/include/ct/external/cppad/cg/arithmetic_ad.hpp b/ct_core/include/ct/external/cppad/cg/arithmetic_ad.hpp deleted file mode 100644 index 8ec31c3db..000000000 --- a/ct_core/include/ct/external/cppad/cg/arithmetic_ad.hpp +++ /dev/null @@ -1,68 +0,0 @@ -#ifndef CPPAD_CG_ARITHMETIC_AD_INCLUDED -#define CPPAD_CG_ARITHMETIC_AD_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/******************************************************************************* - * Operations with AD (resolves ambiguity) - ******************************************************************************/ -template -inline AD > operator+(const CG& left, const AD >& right) { - return CppAD::operator+(left, right); -} - -template -inline AD > operator+(const AD >& left, const CG& right) { - return CppAD::operator+(left, right); -} - -template -inline AD > operator-(const CG& left, const AD >& right) { - return CppAD::operator-(left, right); -} - -template -inline AD > operator-(const AD >& left, const CG& right) { - return CppAD::operator-(left, right); -} - -template -inline AD > operator/(const CG& left, const AD >& right) { - return CppAD::operator/(left, right); -} - -template -inline AD > operator/(const AD >& left, const CG& right) { - return CppAD::operator/(left, right); -} - -template -inline AD > operator*(const CG& left, const AD >& right) { - return CppAD::operator*(left, right); -} - -template -inline AD > operator*(const AD >& left, const CG& right) { - return CppAD::operator*(left, right); -} - -} // END cg namespace -} // END CppAD namespace - -#endif - diff --git a/ct_core/include/ct/external/cppad/cg/arithmetic_assign.hpp b/ct_core/include/ct/external/cppad/cg/arithmetic_assign.hpp deleted file mode 100644 index 78f5a7740..000000000 --- a/ct_core/include/ct/external/cppad/cg/arithmetic_assign.hpp +++ /dev/null @@ -1,220 +0,0 @@ -#ifndef CPPAD_CG_ARITHMETIC_ASSIGN_INCLUDED -#define CPPAD_CG_ARITHMETIC_ASSIGN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -inline CG& CG::operator+=(const CG &right) { - if (isParameter() && right.isParameter()) { - *value_ += *right.value_; - - } else { - CodeHandler* handler; - if (isParameter()) { - if (isIdenticalZero()) { - *this = right; - return *this; - } - - handler = right.node_->getCodeHandler(); - - } else if (right.isParameter()) { - if (right.isIdenticalZero()) { - return *this; // nothing to do - } - - handler = node_->getCodeHandler(); - - } else { // both left and right hand sides are variables - CPPADCG_ASSERT_UNKNOWN(node_->getCodeHandler() == right.node_->getCodeHandler()); - handler = node_->getCodeHandler(); - } - - std::unique_ptr value; - if (isValueDefined() && right.isValueDefined()) { - value.reset(new Base(getValue() + right.getValue())); - } - - makeVariable(*handler->makeNode(CGOpCode::Add,{argument(), right.argument()}), value); - } - - return *this; -} - -template -inline CG& CG::operator-=(const CG &right) { - if (isParameter() && right.isParameter()) { - *value_ -= *right.value_; - - } else { - CodeHandler* handler; - if (isParameter()) { - handler = right.node_->getCodeHandler(); - - } else if (right.isParameter()) { - if (right.isIdenticalZero()) { - return *this; // nothing to do - } - - handler = node_->getCodeHandler(); - - } else { // both left and right hand sides are variables - CPPADCG_ASSERT_UNKNOWN(node_->getCodeHandler() == right.node_->getCodeHandler()); - handler = node_->getCodeHandler(); - } - - std::unique_ptr value; - if (isValueDefined() && right.isValueDefined()) { - value.reset(new Base(getValue() - right.getValue())); - } - - makeVariable(*handler->makeNode(CGOpCode::Sub,{argument(), right.argument()}), value); - } - - return *this; -} - -template -inline CG& CG::operator*=(const CG &right) { - if (isParameter() && right.isParameter()) { - *value_ *= *right.value_; - - } else { - CodeHandler* handler; - if (isParameter()) { - if (isIdenticalZero()) { - return *this; // nothing to do (does not consider that right might be infinity) - } else if (isIdenticalOne()) { - *this = right; - return *this; - } - - handler = right.node_->getCodeHandler(); - - } else if (right.isParameter()) { - if (right.isIdenticalZero()) { - makeParameter(Base(0.0)); // does not consider that left might be infinity - return *this; - } else if (right.isIdenticalOne()) { - return *this; // nothing to do - } - - handler = node_->getCodeHandler(); - - } else { // both left and right hand sides are variables - CPPADCG_ASSERT_UNKNOWN(node_->getCodeHandler() == right.node_->getCodeHandler()); - handler = node_->getCodeHandler(); - } - - std::unique_ptr value; - if (isValueDefined() && right.isValueDefined()) { - value.reset(new Base(getValue() * right.getValue())); - } - - makeVariable(*handler->makeNode(CGOpCode::Mul,{argument(), right.argument()}), value); - } - - return *this; -} - -template -inline CG& CG::operator/=(const CG &right) { - if (isParameter() && right.isParameter()) { - *value_ /= *right.value_; - - } else { - CodeHandler* handler; - if (isParameter()) { - if (isIdenticalZero()) { - return *this; // nothing to do (does not consider that right might be infinity or zero) - } - - handler = right.node_->getCodeHandler(); - - } else if (right.isParameter()) { - if (right.isIdenticalOne()) { - return *this; // nothing to do - } - - handler = node_->getCodeHandler(); - - } else { // both left and right hand sides are variables - CPPADCG_ASSERT_UNKNOWN(node_->getCodeHandler() == right.node_->getCodeHandler()); - handler = node_->getCodeHandler(); - } - - std::unique_ptr value; - if (isValueDefined() && right.isValueDefined()) { - value.reset(new Base(getValue() / right.getValue())); - } - - makeVariable(*handler->makeNode(CGOpCode::Div,{argument(), right.argument()}), value); - } - - return *this; -} - -template -inline CG& CG::operator+=(const Base &right) { - return operator+=(CG (right)); -} - -template -inline CG& CG::operator-=(const Base &right) { - return operator-=(CG (right)); -} - -template -inline CG& CG::operator/=(const Base &right) { - return operator/=(CG (right)); -} - -template -inline CG& CG::operator*=(const Base &right) { - return operator*=(CG (right)); -} - -template -template -inline CG& CG::operator+=(const T &right) { - return operator+=(CG (right)); -} - -template -template -inline CG& CG::operator-=(const T &right) { - return operator-=(CG (right)); -} - -template -template -inline CG& CG::operator/=(const T &right) { - return operator/=(CG (right)); -} - -template -template -inline CG& CG::operator*=(const T &right) { - return operator*=(CG (right)); -} - -} // END cg namespace -} // END CppAD namespace - -#endif - diff --git a/ct_core/include/ct/external/cppad/cg/array_id_compresser.hpp b/ct_core/include/ct/external/cppad/cg/array_id_compresser.hpp deleted file mode 100644 index 34b73c209..000000000 --- a/ct_core/include/ct/external/cppad/cg/array_id_compresser.hpp +++ /dev/null @@ -1,240 +0,0 @@ -#ifndef CPPAD_CG_ARRAY_COMPRESSER_INCLUDED -#define CPPAD_CG_ARRAY_COMPRESSER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Arrays in generated source can reuse space from a global array. - * Positions for each array can be determined using this class. - * Array locations are stored in node IDs as: id = location + 1. - */ -template -class ArrayIdCompresser { -private: - /** - * [start] = end - */ - std::map _freeArrayStartSpace; - /** - * [end] = start - */ - std::map _freeArrayEndSpace; - /** - * values in temporary array - */ - std::vector*> _tmpArrayValues; - /** - * Variable IDs - */ - CodeHandlerVector& _varId; - /** - * Maximum array id - */ - size_t _idArrayCount; -public: - - /** - * Creates an ArrayIdCompresser - * @param maxArraySize The likely number of elements in the temporary array - */ - inline ArrayIdCompresser(CodeHandlerVector& varId, - size_t maxArraySize) : - _tmpArrayValues(maxArraySize, nullptr), - _varId(varId), - _idArrayCount(1) { - } - - inline size_t getIdCount() const { - return _idArrayCount; - } - - inline void addFreeArraySpace(const OperationNode& released) { - size_t arrayStart = _varId[released] - 1; - const size_t arraySize = released.getArguments().size(); - if (arraySize == 0) - return; // nothing to do (no free space) - size_t arrayEnd = arrayStart + arraySize - 1; - - std::map::iterator it; - if (arrayStart > 0) { - // try to merge with previous free space - it = _freeArrayEndSpace.find(arrayStart - 1); // previous - if (it != _freeArrayEndSpace.end()) { - arrayStart = it->second; // merge space - _freeArrayEndSpace.erase(it); - _freeArrayStartSpace.erase(arrayStart); - } - } - - // try to merge with the next free space - it = _freeArrayStartSpace.find(arrayEnd + 1); // next - if (it != _freeArrayStartSpace.end()) { - arrayEnd = it->second; // merge space - _freeArrayStartSpace.erase(it); - _freeArrayEndSpace.erase(arrayEnd); - } - - _freeArrayStartSpace[arrayStart] = arrayEnd; - _freeArrayEndSpace[arrayEnd] = arrayStart; - - CPPADCG_ASSERT_UNKNOWN(_freeArrayStartSpace.size() == _freeArrayEndSpace.size()); - } - - inline size_t reserveArraySpace(const OperationNode& newArray) { - size_t arraySize = newArray.getArguments().size(); - - if (arraySize == 0) - return 0; // nothing to do (no space required) - - std::set blackList; - const std::vector >& args = newArray.getArguments(); - for (size_t i = 0; i < args.size(); i++) { - const OperationNode* argOp = args[i].getOperation(); - if (argOp != nullptr && argOp->getOperationType() == CGOpCode::ArrayElement) { - const OperationNode& otherArray = *argOp->getArguments()[0].getOperation(); - CPPADCG_ASSERT_UNKNOWN(_varId[otherArray] > 0); // make sure it had already been assigned space - size_t otherArrayStart = _varId[otherArray] - 1; - size_t index = argOp->getInfo()[0]; - blackList.insert(otherArrayStart + index); - } - } - - /** - * Find the best location for the new array - */ - std::map::reverse_iterator it; - std::map::reverse_iterator itBestFit = _freeArrayStartSpace.rend(); - size_t bestCommonValues = 0; // the number of values likely to be the same - for (it = _freeArrayStartSpace.rbegin(); it != _freeArrayStartSpace.rend(); ++it) { - size_t start = it->first; - size_t end = it->second; - size_t space = end - start + 1; - if (space < arraySize) { - continue; - } - - std::set::const_iterator itBlack = blackList.lower_bound(start); - if (itBlack != blackList.end() && *itBlack <= end) { - continue; // cannot use this space - } - - //possible candidate - if (itBestFit == _freeArrayStartSpace.rend()) { - itBestFit = it; - } else { - size_t bestSpace = itBestFit->second - itBestFit->first + 1; - - size_t commonVals = 0; - for (size_t i = 0; i < arraySize; i++) { - if (isSameArrayElement(_tmpArrayValues[start + i], args[i])) { - commonVals++; - } - } - - if (space < bestSpace || commonVals > bestCommonValues) { - // better fit - itBestFit = it; - bestCommonValues = commonVals; - if (bestCommonValues == arraySize) { - break; // jackpot - } - } - } - } - - size_t bestStart = std::numeric_limits::max(); - if (itBestFit != _freeArrayStartSpace.rend()) { - /** - * Use available space - */ - bestStart = itBestFit->first; - size_t bestEnd = itBestFit->second; - size_t bestSpace = bestEnd - bestStart + 1; - _freeArrayStartSpace.erase(bestStart); - if (bestSpace == arraySize) { - // entire space - _freeArrayEndSpace.erase(bestEnd); - } else { - // some space left - size_t newFreeStart = bestStart + arraySize; - _freeArrayStartSpace[newFreeStart] = bestEnd; - _freeArrayEndSpace.at(bestEnd) = newFreeStart; - } - - } else { - /** - * no space available, need more - */ - // check if there is some free space at the end - std::map::iterator itEnd; - itEnd = _freeArrayEndSpace.find(_idArrayCount - 1 - 1); // IDcount - initialID - 1 - if (itEnd != _freeArrayEndSpace.end()) { - // check if it can be used - size_t lastSpotStart = itEnd->second; - size_t lastSpotEnd = itEnd->first; - size_t lastSpotSize = lastSpotEnd - lastSpotStart + 1; - std::set::const_iterator itBlack = blackList.lower_bound(lastSpotStart); - if (itBlack == blackList.end()) { - // can use this space - _freeArrayEndSpace.erase(itEnd); - _freeArrayStartSpace.erase(lastSpotStart); - - _idArrayCount += arraySize - lastSpotSize; - bestStart = lastSpotStart; - } - } - - if (bestStart == std::numeric_limits::max()) { - // brand new space - size_t id = _idArrayCount; - _idArrayCount += arraySize; - bestStart = id - 1; - } - } - - for (size_t i = 0; i < arraySize; i++) { - _tmpArrayValues[bestStart + i] = &args[i]; - } - - CPPADCG_ASSERT_UNKNOWN(_freeArrayStartSpace.size() == _freeArrayEndSpace.size()); - - return bestStart; - } - - inline static bool isSameArrayElement(const Argument* oldArg, - const Argument& arg) { - if (oldArg != nullptr) { - if (oldArg->getParameter() != nullptr) { - if (arg.getParameter() != nullptr) { - return (*arg.getParameter() == *oldArg->getParameter()); - } - } else { - return (arg.getOperation() == oldArg->getOperation()); - } - } - return false; - } - - virtual ~ArrayIdCompresser() { - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/array_wrapper.hpp b/ct_core/include/ct/external/cppad/cg/array_wrapper.hpp deleted file mode 100644 index d86730d35..000000000 --- a/ct_core/include/ct/external/cppad/cg/array_wrapper.hpp +++ /dev/null @@ -1,333 +0,0 @@ -#ifndef CPPAD_CG_ARRAY_WRAPPER_INCLUDED -#define CPPAD_CG_ARRAY_WRAPPER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -# include -# include -# include - -namespace CppAD { -namespace cg { - -/** - * A simple wrapper for C arrays. - * It does not own the data array. - */ -template -class ArrayWrapper { -public: - typedef Type value_type; - typedef value_type* pointer; - typedef const value_type* const_pointer; - typedef value_type& reference; - typedef const Type& const_reference; - typedef value_type* iterator; - typedef const value_type* const_iterator; - typedef std::reverse_iterator const_reverse_iterator; - typedef std::reverse_iterator reverse_iterator; - typedef size_t size_type; - typedef ptrdiff_t difference_type; -private: - /** - * The externally created array - */ - pointer _data; - /** - * The number of elements in the array - */ - size_type _length; -public: - /** - * Default empty constructor for arrays with no elements - */ - inline ArrayWrapper() : - _data(nullptr), - _length(0) { - } - - /** - * Creates a wrapper for an existing array. - * - * @param array pointer to the first element of the array - * @param n size of the array - */ - inline ArrayWrapper(pointer array, - size_type n) : - _data(array), - _length(n) { - } - - /** - * Creates a wrapper from a vector. - * It is expected that the vector is not resized while using this wrapper. - * - * @param vector the vector to wrap - */ - inline ArrayWrapper(std::vector& vector) : - _data(vector.data()), - _length(vector.size()) { - } - - /** - * Creates a wrapper from a vector. - * It is expected that the vector is not resized while using this wrapper. - * - * @param vector the vector to wrap - */ - inline ArrayWrapper(CppAD::vector& vector) : - _data(vector.data()), - _length(vector.size()) { - } - - /** - * Creates a wrapper from a vector. - * It is expected that the vector is not resized while using this wrapper. - * - * @param vector the vector to wrap - */ - template - inline ArrayWrapper(const std::vector::type>& vector, - typename std::enable_if::value>::type* = 0) : - _data(vector.data()), - _length(vector.size()) { - } - - /** - * Creates a wrapper from a vector. - * It is expected that the vector is not resized while using this wrapper. - * - * @param vector the vector to wrap - */ - template - inline ArrayWrapper(const CppAD::vector::type>& vector, - typename std::enable_if::value>::type* = 0) : - _data(vector.data()), - _length(vector.size()) { - } - - /** - * Copy constructor - * @param x - */ - inline ArrayWrapper(const ArrayWrapper& x) = default; - - /** - * Desctructor - */ - virtual ~ArrayWrapper() = default; - - /** - * @return number of elements in the array. - */ - inline size_t size() const noexcept { - return _length; - } - - /** - * @return number of elements in the array. - */ - inline size_type max_size() const noexcept { - return _length; - } - - inline bool empty() const noexcept { - return size() == 0; - } - - /** - * @return raw pointer to the array - */ - inline pointer data() noexcept { - return _data; - } - - /** - * @return raw pointer to the array - */ - inline const_pointer data() const noexcept { - return _data; - } - - inline void fill(const value_type& u) { - std::fill_n(begin(), size(), u); - } - - inline void swap(ArrayWrapper& other) noexcept { - std::swap(other._data, _data); - std::swap(other._length, _length); - } - - // Iterators. - inline iterator begin() noexcept { - return iterator(data()); - } - - inline const_iterator begin() const noexcept { - return const_iterator(data()); - } - - inline iterator end() noexcept { - return iterator(data() + size()); - } - - inline const_iterator end() const noexcept { - return const_iterator(data() + size()); - } - - inline reverse_iterator rbegin() noexcept { - return reverse_iterator(end()); - } - - inline const_reverse_iterator rbegin() const noexcept { - return const_reverse_iterator(end()); - } - - inline reverse_iterator rend() noexcept { - return reverse_iterator(begin()); - } - - inline const_reverse_iterator rend() const noexcept { - return const_reverse_iterator(begin()); - } - - inline const_iterator cbegin() const noexcept { - return const_iterator(data()); - } - - inline const_iterator cend() const noexcept { - return const_iterator(data() + size()); - } - - inline const_reverse_iterator crbegin() const noexcept { - return const_reverse_iterator(end()); - } - - inline const_reverse_iterator crend() const noexcept { - return const_reverse_iterator(begin()); - } - - // Element access. - inline reference operator[](size_type i) { - CPPAD_ASSERT_KNOWN(i < size(), "ArrayWrapper: index greater than or equal array size"); - return _data[i]; - } - - inline const_reference operator[](size_type i) const { - CPPADCG_ASSERT_KNOWN(i < size(), "ArrayWrapper: index greater than or equal array size"); - return _data[i]; - } - - inline reference at(size_type i) { - if (i >= size()) - throw CGException("ArrayWrapper::at() index ", i, " is greater than or equal array size ", size()); - return _data[i]; - } - - inline const_reference at(size_type i) const { - if (i >= size()) - throw CGException("ArrayWrapper::at() index ", i, " is greater than or equal array size ", size()); - return _data[i]; - } - - inline reference front() { - CPPADCG_ASSERT_KNOWN(!empty(), "ArrayWrapper: cannot call front for an empty array"); - return *begin(); - } - - inline const_reference front() const { - CPPADCG_ASSERT_KNOWN(!empty(), "ArrayWrapper: cannot call front for an empty array"); - return _data[0]; - } - - inline reference back() { - CPPADCG_ASSERT_KNOWN(!empty(), "ArrayWrapper: cannot call back for an empty array"); - return *(end() - 1); - } - - inline const_reference back() const { - CPPADCG_ASSERT_KNOWN(!empty(), "ArrayWrapper: cannot call back for an empty array"); - return _data[size() - 1]; - } - -public: - inline ArrayWrapper& operator=(const ArrayWrapper& x) { - if (&x == this) - return *this; - - if (x.size() != size()) - throw CGException("ArrayWrapper: assigning an array with different size: the left hand side array has the size ", size(), - " while the right hand side array has the size ", x.size(), "."); - - for(size_t i = 0; i < _length; ++i) { - _data[i] = x._data[i]; - } - - return *this; - } - - inline ArrayWrapper& operator=(const std::vector& x) { - if (x.size() != size()) - throw CGException("ArrayWrapper: assigning an array with different size: the left hand side array has the size ", size(), - " while the right hand side array has the size ", x.size(), "."); - - for(size_t i = 0; i < _length; ++i) { - _data[i] = x[i]; - } - - return *this; - } - - inline ArrayWrapper& operator=(const CppAD::vector& x) { - if (x.size() != size()) - throw CGException("ArrayWrapper: assigning an array with different size: the left hand side array has the size ", size(), - " while the right hand side array has the size ", x.size(), "."); - - for(size_t i = 0; i < _length; ++i) { - _data[i] = x[i]; - } - - return *this; - } - -}; - -/** - * ArrayWrapper output. - * - * @param os stream to write the vector to - * @param array array that is output - * @return the original stream - */ -template -inline std::ostream& operator<<(std::ostream& os, - const ArrayWrapper& array) { - size_t i = 0; - size_t n = array.size(); - - os << "{ "; - while (i < n) { - os << array[i++]; - if (i < n) - os << ", "; - } - os << " }"; - return os; -} - -} // END cg namespace -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/cg/atomic_dependency_locator.hpp b/ct_core/include/ct/external/cppad/cg/atomic_dependency_locator.hpp deleted file mode 100644 index 4a55c73e1..000000000 --- a/ct_core/include/ct/external/cppad/cg/atomic_dependency_locator.hpp +++ /dev/null @@ -1,99 +0,0 @@ -#ifndef CPPAD_CG_ATOMIC_DEPENDENCY_LOCATOR_INCLUDED -#define CPPAD_CG_ATOMIC_DEPENDENCY_LOCATOR_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -class AtomicDependencyLocator { -private: - ADFun >& fun_; - std::map > atomicIndeps_; - std::map*, std::set > indeps_; - CodeHandler handler_; -public: - - inline AtomicDependencyLocator(ADFun >& fun) : - fun_(fun) { - } - - inline std::map > findAtomicsUsage() { - if (!atomicIndeps_.empty()) { - return atomicIndeps_; - } - - size_t m = fun_.Range(); - size_t n = fun_.Domain(); - - std::vector > x(n); - handler_.makeVariables(x); - - // make sure the position in the code handler is the same as the independent index - assert(x.size() == 0 || (x[0].getOperationNode()->getHandlerPosition() == 0 && x[x.size() - 1].getOperationNode()->getHandlerPosition() == x.size() - 1)); - - std::vector > dep = fun_.Forward(0, x); - - for (size_t i = 0; i < m; i++) { - findAtomicsUsage(dep[i].getOperationNode()); - } - - return atomicIndeps_; - } - -private: - - inline std::set findAtomicsUsage(OperationNode* node) { - if (node == nullptr) - return std::set(); - - CGOpCode op = node->getOperationType(); - if (op == CGOpCode::Inv) { - std::set indeps; - // particular case where the position in the code handler is the same as the independent index - indeps.insert(node->getHandlerPosition()); - return indeps; - } - - if (handler_.isVisited(*node)) { - // been here before - return indeps_.at(node); - } - - handler_.markVisited(*node); - - std::set indeps; - const std::vector >& args = node->getArguments(); - for (size_t a = 0; a < args.size(); a++) { - std::set aindeps = findAtomicsUsage(args[a].getOperation()); - indeps.insert(aindeps.begin(), aindeps.end()); - } - indeps_[node] = indeps; - - if (op == CGOpCode::AtomicForward) { - CPPADCG_ASSERT_UNKNOWN(node->getInfo().size() > 1); - size_t id = node->getInfo()[0]; - atomicIndeps_[id].insert(indeps.begin(), indeps.end()); - } - - return indeps; - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/atomic_fun.hpp b/ct_core/include/ct/external/cppad/cg/atomic_fun.hpp deleted file mode 100644 index 573507ee5..000000000 --- a/ct_core/include/ct/external/cppad/cg/atomic_fun.hpp +++ /dev/null @@ -1,147 +0,0 @@ -#ifndef CPPAD_CG_ATOMIC_FUN_INCLUDED -#define CPPAD_CG_ATOMIC_FUN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * An atomic function for source code generation - * - * @author Joao Leal - */ -template -class CGAtomicFun : public CGAbstractAtomicFun { -protected: - atomic_base& atomicFun_; -public: - - /** - * Creates a new atomic function wrapper that is responsible for - * defining the dependencies to calls of a user atomic function. - * - * @param atomicFun The atomic function to the called by the compiled - * source. - * @param standAlone Whether or not forward and reverse function calls - * do not require the Taylor coefficients for the - * dependent variables (ty) and the previous - * evaluation of other forward/reverse modes. - */ - CGAtomicFun(atomic_base& atomicFun, bool standAlone = false) : - CGAbstractAtomicFun(atomicFun.afun_name(), standAlone), - atomicFun_(atomicFun) { - - } - - template - void operator()(const ADVector& ax, ADVector& ay, size_t id = 0) { - this->CGAbstractAtomicFun::operator()(ax, ay, id); - } - - virtual bool for_sparse_jac(size_t q, - const CppAD::vector< std::set >& r, - CppAD::vector< std::set >& s) override { - return atomicFun_.for_sparse_jac(q, r, s); - } - - virtual bool for_sparse_jac(size_t q, - const CppAD::vector& r, - CppAD::vector& s) override { - return atomicFun_.for_sparse_jac(q, r, s); - } - - virtual bool rev_sparse_jac(size_t q, - const CppAD::vector< std::set >& rt, - CppAD::vector< std::set >& st) override { - return atomicFun_.rev_sparse_jac(q, rt, st); - } - - virtual bool rev_sparse_jac(size_t q, - const CppAD::vector& rt, - CppAD::vector& st) override { - return atomicFun_.rev_sparse_jac(q, rt, st); - } - - virtual bool rev_sparse_hes(const CppAD::vector& vx, - const CppAD::vector& s, - CppAD::vector& t, - size_t q, - const CppAD::vector< std::set >& r, - const CppAD::vector< std::set >& u, - CppAD::vector< std::set >& v) override { - return atomicFun_.rev_sparse_hes(vx, s, t, q, r, u, v); - } - - virtual bool rev_sparse_hes(const CppAD::vector& vx, - const CppAD::vector& s, - CppAD::vector& t, - size_t q, - const CppAD::vector& r, - const CppAD::vector& u, - CppAD::vector& v) override { - return atomicFun_.rev_sparse_hes(vx, s, t, q, r, u, v); - } - - virtual ~CGAtomicFun() { - } - -protected: - - virtual void zeroOrderDependency(const CppAD::vector& vx, - CppAD::vector& vy) override { - using CppAD::vector; - - size_t m = vy.size(); - size_t n = vx.size(); - - vector > rt(m); - for (size_t j = 0; j < m; j++) { - rt[j].insert(j); - } - vector > st(n); - - rev_sparse_jac(m, rt, st); - - for (size_t j = 0; j < n; j++) { - for (size_t i : st[j]) { - if (vx[j]) { - vy[i] = true; - } - } - } - } - - virtual bool atomicForward(size_t q, - size_t p, - const CppAD::vector& tx, - CppAD::vector& ty) override { - CppAD::vector vx, vy; - return atomicFun_.forward(q, p, vx, vy, tx, ty); - } - - virtual bool atomicReverse(size_t p, - const CppAD::vector& tx, - const CppAD::vector& ty, - CppAD::vector& px, - const CppAD::vector& py) override { - return atomicFun_.reverse(p, tx, ty, px, py); - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/atomic_fun_bridge.hpp b/ct_core/include/ct/external/cppad/cg/atomic_fun_bridge.hpp deleted file mode 100644 index 6db107c3d..000000000 --- a/ct_core/include/ct/external/cppad/cg/atomic_fun_bridge.hpp +++ /dev/null @@ -1,321 +0,0 @@ -#ifndef CPPAD_CG_ATOMIC_FUN_BRIDGE_INCLUDED -#define CPPAD_CG_ATOMIC_FUN_BRIDGE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * An atomic function wrapper for atomic functions using the ::CppAD::cg::CG - * type. - * This class can be useful when a CppAD::ADFun is going to - * be used to create a compiled model library but has not been compiled yet. - * - * @author Joao Leal - */ -template -class CGAtomicFunBridge : public CGAbstractAtomicFun { -public: - typedef CppAD::cg::CG CGB; - typedef CppAD::AD ADCGD; -protected: - ADFun& fun_; - bool cacheSparsities_; - CustomPosition custom_jac_; - CustomPosition custom_hess_; - std::map > > hess_; -public: - - /** - * Creates a new atomic function wrapper. - * - * @param name The atomic function name - * @param fun The atomic function to be wrapped - * @param standAlone Whether or not forward and reverse function calls - * do not require the Taylor coefficients for the - * dependent variables (ty) and the previous - * evaluation of other forward/reverse modes. - * @param cacheSparsities Whether or not to cache information related - * with sparsity evaluation. - */ - CGAtomicFunBridge(const std::string& name, - CppAD::ADFun& fun, - bool standAlone = false, - bool cacheSparsities = true) : - CGAbstractAtomicFun(name, standAlone), - fun_(fun), - cacheSparsities_(cacheSparsities) { - this->option(CppAD::atomic_base::set_sparsity_enum); - } - - CGAtomicFunBridge(const CGAtomicFunBridge& orig) = delete; - CGAtomicFunBridge& operator=(const CGAtomicFunBridge& rhs) = delete; - - template - void operator()(const ADVector& ax, ADVector& ay, size_t id = 0) { - this->CGAbstractAtomicFun::operator()(ax, ay, id); - } - - template - inline void setCustomSparseJacobianElements(const VectorSize& row, - const VectorSize& col) { - custom_jac_ = CustomPosition(fun_.Range(), fun_.Domain(), row, col); - } - - template - inline void setCustomSparseJacobianElements(const VectorSet& elements) { - custom_jac_ = CustomPosition(fun_.Range(), fun_.Domain(), elements); - } - - template - inline void setCustomSparseHessianElements(const VectorSize& row, - const VectorSize& col) { - size_t n = fun_.Domain(); - custom_hess_ = CustomPosition(n, n, row, col); - } - - template - inline void setCustomSparseHessianElements(const VectorSet& elements) { - size_t n = fun_.Domain(); - custom_hess_ = CustomPosition(n, n, elements); - } - - virtual bool for_sparse_jac(size_t q, - const CppAD::vector >& r, - CppAD::vector >& s) { - using CppAD::vector; - - if (cacheSparsities_ || custom_jac_.isFilterDefined()) { - size_t n = fun_.Domain(); - size_t m = fun_.Range(); - if (!custom_jac_.isFullDefined()) { - custom_jac_.setFullElements(jacobianForwardSparsitySet > >(fun_)); - fun_.size_forward_set(0); - } - - for (size_t i = 0; i < s.size(); i++) { - s[i].clear(); - } - CppAD::cg::multMatrixMatrixSparsity(custom_jac_.getFullElements(), r, s, m, n, q); - } else { - s = fun_.ForSparseJac(q, r); - fun_.size_forward_set(0); - } - - return true; - } - - virtual bool rev_sparse_jac(size_t q, - const CppAD::vector >& rt, - CppAD::vector >& st) { - using CppAD::vector; - - if (cacheSparsities_ || custom_jac_.isFilterDefined()) { - size_t n = fun_.Domain(); - size_t m = fun_.Range(); - if (!custom_jac_.isFullDefined()) { - custom_jac_.setFullElements(jacobianReverseSparsitySet > >(fun_)); - } - - for (size_t i = 0; i < st.size(); i++) { - st[i].clear(); - } - CppAD::cg::multMatrixMatrixSparsityTrans(rt, custom_jac_.getFullElements(), st, m, n, q); - } else { - st = fun_.RevSparseJac(q, rt, true); - } - - return true; - } - - virtual bool rev_sparse_hes(const CppAD::vector& vx, - const CppAD::vector& s, - CppAD::vector& t, - size_t q, - const CppAD::vector >& r, - const CppAD::vector >& u, - CppAD::vector >& v) { - using CppAD::vector; - - if (cacheSparsities_ || custom_jac_.isFilterDefined() || custom_hess_.isFilterDefined()) { - size_t n = fun_.Domain(); - size_t m = fun_.Range(); - - for (size_t i = 0; i < n; i++) { - v[i].clear(); - } - - if (!custom_jac_.isFullDefined()) { - custom_jac_.setFullElements(jacobianSparsitySet > >(fun_)); - } - const std::vector >& jacSparsity = custom_jac_.getFullElements(); - - /** - * V(x) = f'^T(x) U(x) + Sum( s(x)i f''(x) R(x) ) - */ - // f'^T(x) U(x) - CppAD::cg::multMatrixTransMatrixSparsity(jacSparsity, u, v, m, n, q); - - // Sum( s(x)i f''(x) R(x) ) - bool allSelected = true; - for (size_t i = 0; i < m; i++) { - if (!s[i]) { - allSelected = false; - break; - } - } - - if (allSelected) { - if (!custom_hess_.isFullDefined()) { - custom_hess_.setFullElements(hessianSparsitySet > >(fun_)); // f''(x) - } - const std::vector >& sF2 = custom_hess_.getFullElements(); - CppAD::cg::multMatrixTransMatrixSparsity(sF2, r, v, n, n, q); // f''^T * R - } else { - vector > sparsitySF2R(n); - for (size_t i = 0; i < m; i++) { - if (s[i]) { - const auto itH = hess_.find(i); - const vector >* spari; - if (itH == hess_.end()) { - vector >& hi = hess_[i] = hessianSparsitySet > >(fun_, i); // f''_i(x) - spari = &hi; - custom_hess_.filter(hi); - } else { - spari = &itH->second; - } - CppAD::cg::addMatrixSparsity(*spari, sparsitySF2R); - } - } - CppAD::cg::multMatrixTransMatrixSparsity(sparsitySF2R, r, v, n, n, q); // f''^T * R - } - - /** - * S(x) * f'(x) - */ - for (size_t i = 0; i < m; i++) { - if (s[i]) { - for (size_t j : jacSparsity[i]) { - t[j] = true; - } - } - } - } else { - size_t m = fun_.Range(); - size_t n = fun_.Domain(); - - t = fun_.RevSparseJac(1, s); - vector > a = fun_.RevSparseJac(q, u, true); - - // set version of s - vector > set_s(1); - for (size_t i = 0; i < m; i++) { - if (s[i]) - set_s[0].insert(i); - } - - fun_.ForSparseJac(q, r); - v = fun_.RevSparseHes(q, set_s, true); - - for (size_t i = 0; i < n; i++) { - for (size_t j : a[i]) { - CPPAD_ASSERT_UNKNOWN(j < q); - v[i].insert(j); - } - } - - fun_.size_forward_set(0); - } - - return true; - } - - virtual ~CGAtomicFunBridge() { - } - -protected: - - virtual void zeroOrderDependency(const CppAD::vector& vx, - CppAD::vector& vy) { - CppAD::cg::zeroOrderDependency(fun_, vx, vy); - } - - virtual bool atomicForward(size_t q, - size_t p, - const CppAD::vector& tx, - CppAD::vector& ty) { - using CppAD::vector; - - vector txcg(tx.size()); - toCG(tx, txcg); - - vector tycg = fun_.Forward(p, txcg); - fromCG(tycg, ty); - - fun_.capacity_order(0); - - return true; - } - - virtual bool atomicReverse(size_t p, - const CppAD::vector& tx, - const CppAD::vector& ty, - CppAD::vector& px, - const CppAD::vector& py) { - using CppAD::vector; - - vector txcg(tx.size()); - vector pycg(py.size()); - - toCG(tx, txcg); - toCG(py, pycg); - - fun_.Forward(p, txcg); - - vector pxcg = fun_.Reverse(p + 1, pycg); - fromCG(pxcg, px); - - fun_.capacity_order(0); - return true; - } - -private: - - static void toCG(const CppAD::vector& from, - CppAD::vector& to) { - CPPAD_ASSERT_UNKNOWN(from.size() == to.size()); - - for (size_t i = 0; i < from.size(); i++) { - to[i] = from[i]; - } - } - - static void fromCG(const CppAD::vector& from, - CppAD::vector& to) { - CPPAD_ASSERT_UNKNOWN(from.size() == to.size()); - - for (size_t i = 0; i < from.size(); i++) { - CPPADCG_ASSERT_KNOWN(from[i].isValueDefined(), "No value defined") - to[i] = from[i].getValue(); - } - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/base_abstract_atomic_fun.hpp b/ct_core/include/ct/external/cppad/cg/base_abstract_atomic_fun.hpp deleted file mode 100644 index a927fb656..000000000 --- a/ct_core/include/ct/external/cppad/cg/base_abstract_atomic_fun.hpp +++ /dev/null @@ -1,152 +0,0 @@ -#ifndef CPPAD_CG_BASE_ABSTRACT_ATOMIC_FUN_INCLUDED -#define CPPAD_CG_BASE_ABSTRACT_ATOMIC_FUN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Contains some utility methods for atomic functions - * - * @author Joao Leal - */ -template -class BaseAbstractAtomicFun : public atomic_base > { -public: - typedef CppAD::cg::CG CGB; - typedef Argument Arg; -protected: - - /** - * Creates a new atomic function that is responsible for defining the - * dependencies to calls of a user atomic function. - * - * @param name The atomic function name. - */ - BaseAbstractAtomicFun(const std::string& name) : - atomic_base(name) { - CPPADCG_ASSERT_KNOWN(!name.empty(), "The atomic function name cannot be empty"); - } - -public: - - template - void operator()(const ADVector& ax, ADVector& ay, size_t id = 0) { - this->atomic_base::operator()(ax, ay, id); - } - - virtual ~BaseAbstractAtomicFun() { - } - -protected: - - static inline void appendAsArguments(typename std::vector::iterator begin, - const CppAD::vector& tx) { - std::vector arguments(tx.size()); - typename std::vector::iterator it = begin; - for (size_t i = 0; i < arguments.size(); i++, ++it) { - if (tx[i].isParameter()) { - *it = Arg(tx[i].getValue()); - } else { - *it = Arg(*tx[i].getOperationNode()); - } - } - } - - static inline OperationNode* makeArray(CodeHandler& handler, - const CppAD::vector& tx) { - std::vector arrayArgs = asArguments(tx); - std::vector info; // empty - - return handler.makeNode(CGOpCode::ArrayCreation, info, arrayArgs); - } - - static inline OperationNode* makeArray(CodeHandler& handler, - const CppAD::vector& tx, - size_t p, - size_t k) { - CPPADCG_ASSERT_UNKNOWN(k <= p); - size_t n = tx.size() / (p + 1); - std::vector arrayArgs(n); - for (size_t i = 0; i < n; i++) { - arrayArgs[i] = asArgument(tx[i * (p + 1) + k]); - } - - return handler.makeNode(CGOpCode::ArrayCreation,{}, arrayArgs); - } - - static inline OperationNode* makeZeroArray(CodeHandler& handler, - size_t size) { - CppAD::vector tx2(size); - std::vector arrayArgs = asArguments(tx2); - - return handler.makeNode(CGOpCode::ArrayCreation,{}, arrayArgs); - } - - static inline OperationNode* makeEmptySparseArray(CodeHandler& handler, - size_t size) { - return handler.makeNode(CGOpCode::SparseArrayCreation,{size}, {}); //empty args - } - - static inline OperationNode* makeSparseArray(CodeHandler& handler, - const CppAD::vector& py, - size_t p, - size_t k) { - size_t p1 = p + 1; - CPPADCG_ASSERT_UNKNOWN(k < p1); - size_t n = py.size() / p1; - - std::vector arrayArgs; - std::vector arrayIdx(1); - arrayIdx[0] = n; // array size - - arrayArgs.reserve(py.size() / 3); - arrayIdx.reserve(1 + py.size() / 3); - - for (size_t i = 0; i < n; i++) { - if (!py[i * p1 + k].isIdenticalZero()) { - arrayArgs.push_back(asArgument(py[i * p1 + k])); - arrayIdx.push_back(i); - } - } - - return handler.makeNode(CGOpCode::SparseArrayCreation, arrayIdx, arrayArgs); - } - - static inline bool isParameters(const CppAD::vector& tx) { - for (size_t i = 0; i < tx.size(); i++) { - if (!tx[i].isParameter()) { - return false; - } - } - return true; - } - - static inline bool isValuesDefined(const CppAD::vector& tx) { - for (size_t i = 0; i < tx.size(); i++) { - if (!tx[i].isValueDefined()) { - return false; - } - } - return true; - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/base_double.hpp b/ct_core/include/ct/external/cppad/cg/base_double.hpp deleted file mode 100644 index 2e890475d..000000000 --- a/ct_core/include/ct/external/cppad/cg/base_double.hpp +++ /dev/null @@ -1,67 +0,0 @@ -#ifndef CPPAD_CG_BASE_DOUBLE_INCLUDED -#define CPPAD_CG_BASE_DOUBLE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { - -/** - * Specialization of the numeric_limits for doubles - */ -template <> -class numeric_limits > { -public: - - static cg::CG epsilon() { - return std::numeric_limits::epsilon(); - } - - static cg::CG min() { - return std::numeric_limits::min(); - } - - static cg::CG max() { - return std::numeric_limits::max(); - } - - static cg::CG quiet_NaN() { - return std::numeric_limits::quiet_NaN(); - } - -}; - -/** - * Specialization of the machine epsilon for CG - */ -template <> -inline cg::CG epsilon >() { - return std::numeric_limits::epsilon(); -} - -/** - * Absolute Zero multiplication - */ -inline cg::CG azmul(const cg::CG& x, const cg::CG& y) { - cg::CG zero(0.0); - if (x == zero) - return zero; - return x * y; -} -//CPPAD_AZMUL( cg::CG ) - -} // END CppAD namespace - -#endif - diff --git a/ct_core/include/ct/external/cppad/cg/base_float.hpp b/ct_core/include/ct/external/cppad/cg/base_float.hpp deleted file mode 100644 index 56d819cf0..000000000 --- a/ct_core/include/ct/external/cppad/cg/base_float.hpp +++ /dev/null @@ -1,67 +0,0 @@ -#ifndef CPPAD_CG_BASE_FLOAT_INCLUDED -#define CPPAD_CG_BASE_FLOAT_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2015 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { - -/** - * Specialization of the numeric_limits for floats - */ -template <> -class numeric_limits > { -public: - - static cg::CG epsilon() { - return std::numeric_limits::epsilon(); - } - - static cg::CG min() { - return std::numeric_limits::min(); - } - - static cg::CG max() { - return std::numeric_limits::max(); - } - - static cg::CG quiet_NaN() { - return std::numeric_limits::quiet_NaN(); - } -}; - -/** - * Specialization of the machine epsilon for CG - */ -template <> -inline cg::CG epsilon >() { - return std::numeric_limits::epsilon(); -} - -/** - * Absolute Zero multiplication - */ -inline cg::CG azmul(const cg::CG& left, - const cg::CG& right) { - cg::CG zero(0.0); - if (left == zero) - return zero; - return left * right; -} -// CPPAD_AZMUL(cg::CG) - -} // END CppAD namespace - -#endif - diff --git a/ct_core/include/ct/external/cppad/cg/bidir_graph.hpp b/ct_core/include/ct/external/cppad/cg/bidir_graph.hpp deleted file mode 100644 index 5009f3139..000000000 --- a/ct_core/include/ct/external/cppad/cg/bidir_graph.hpp +++ /dev/null @@ -1,298 +0,0 @@ -#ifndef CPPAD_CG_BIDIR_GRAPH_INCLUDED -#define CPPAD_CG_BIDIR_GRAPH_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -class PathNodeEdges { -public: - typedef OperationNode Node; - typedef OperationPathNode Path; -public: - std::vector arguments; - std::vector usage; // parent node and argument index in that node -}; - -/** - * Bidirectional graph used to navigate through the operations graph. - */ -template -class BidirGraph { -public: - typedef OperationNode Node; - typedef typename CodeHandler::SourceCodePath SourceCodePath; -private: - std::map > graph_; -public: - inline virtual ~BidirGraph() { } - - inline bool empty() const { - return graph_.empty(); - } - - inline void connect(Node& node, - size_t argument) { - connect(graph_[&node], node, argument); - } - - inline void connect(PathNodeEdges& nodeInfo, - Node& node, - size_t argument) { - CPPADCG_ASSERT_UNKNOWN(argument < node.getArguments().size()); - CPPADCG_ASSERT_UNKNOWN(node.getArguments()[argument].getOperation() != nullptr); - CPPADCG_ASSERT_UNKNOWN(&graph_[&node] == &nodeInfo); - - nodeInfo.arguments.push_back(argument); - - auto* aNode = node.getArguments()[argument].getOperation(); - graph_[aNode].usage.push_back(OperationPathNode(&node, argument)); - } - - inline bool contains(Node& node) const { - auto it = graph_.find(&node); - return it != graph_.end(); - } - - inline PathNodeEdges* find(Node& node) { - auto it = graph_.find(&node); - if (it != graph_.end()) - return &it->second; - else - return nullptr; - } - - inline const PathNodeEdges* find(Node& node) const { - auto it = graph_.find(&node); - if (it != graph_.end()) - return &it->second; - else - return nullptr; - } - - inline bool erase(Node& node) { - return graph_.erase(&node) > 0; - } - - inline PathNodeEdges& operator[](Node& node) { - return graph_[&node]; - } - - /** - * Find a path from node to target without any additional bifurcation along - * the path. - */ - inline std::vector findSingleBifurcation(Node& expression, - Node& target, - size_t& bifIndex) const { - - std::vector paths; - bifIndex = -1; - - if (empty()) { - return paths; - } - - const PathNodeEdges* tail = find(target); - if (tail == nullptr) - return paths; - - paths.reserve(2); - paths.resize(1); - paths[0].reserve(20); // path down - - if (tail->usage.empty()) { - // only one path with one element - paths[0].push_back(OperationPathNode(&target, -1)); - return paths; - } - - paths = findPathUpTo(expression, target); - if (paths.size() > 1) - bifIndex = 0; - - if (paths[0][0].node != &expression) { - /** - * Add a missing path from the nodes at paths[0][0] to the - * expression node - */ - SourceCodePath pathCommon; - - auto* n = paths[0][0].node; - auto* edges = find(*n); - CPPADCG_ASSERT_UNKNOWN(edges != nullptr); // must exist - - while (true) { - n = edges->usage.begin()->node; // ignore other usages for now!!!! - - pathCommon.push_back(*edges->usage.begin()); - if (n == &expression) - break; - - edges = find(*n); - CPPADCG_ASSERT_UNKNOWN(edges != nullptr); - CPPADCG_ASSERT_UNKNOWN(!edges->usage.empty()); - } - - bifIndex = pathCommon.size(); - - std::reverse(pathCommon.begin(), pathCommon.end()); - for (auto& p: paths) - p.insert(p.begin(), pathCommon.begin(), pathCommon.end()); - } - - return paths; - } - -private: - - /** - * Find a path from node to target without any additional bifurcation along the path - */ - std::vector findPathUpTo(Node& node, - Node& target) const { - auto* n = &node; - - auto* edges = find(*n); - CPPADCG_ASSERT_UNKNOWN(edges != nullptr); // must exist - - std::vector paths; - paths.reserve(2); - paths.resize(1); - - while (!edges->arguments.empty()) { - if (edges->arguments.size() > 1) { - // found bifurcation: must restart! - size_t a1Index = edges->arguments[0]; - const auto& a1 = n->getArguments()[a1Index]; - paths = findPathUpTo(*a1.getOperation(), target); - if (paths.size() == 2) { - return paths; - } - - size_t a2Index = edges->arguments[1]; - const auto& a2 = n->getArguments()[a2Index]; - auto paths2 = findPathUpTo(*a2.getOperation(), target); - if (paths2.size() == 2) { - return paths2; - } - - paths[0].insert(paths[0].begin(), OperationPathNode(n, a1Index)); - - paths.resize(2); - paths[1].reserve(paths2[0].size() + 1); - paths[1].insert(paths[1].begin(), OperationPathNode(n, a2Index)); - paths[1].insert(paths[1].begin() + 1, paths2[0].begin(), paths2[0].end()); - return paths; - } - - size_t argIndex1 = *edges->arguments.begin(); // only one argument - paths[0].push_back(OperationPathNode(n, argIndex1)); - - n = n->getArguments()[argIndex1].getOperation(); - edges = find(*n); - CPPADCG_ASSERT_UNKNOWN(edges != nullptr); // must exist - } - - paths[0].push_back(OperationPathNode(n, -1)); - - return paths; - } - -#if 0 - void findPathDownThenUp() { - for (const auto& arg0: tail->usage) { - paths.resize(1); - paths[0].clear(); - paths[0].push_back(OperationPathNode(&target, -1)); - - Node* n = arg0.node; - size_t argIndex = arg0.argIndex; - - const PathNodeEdges* edges = find(*n); - CPPADCG_ASSERT_UNKNOWN(edges != nullptr); - - while (true) { - paths[0].push_back(OperationPathNode(n, argIndex)); - - if(edges->arguments.size() != 1) - break; // a bifurcation - - if(edges->usage.empty()) - break; - n = edges->usage.begin()->node; // ignore other usages for now!!!! - argIndex = edges->usage.begin()->argIndex; - - edges = find(*n); - CPPADCG_ASSERT_UNKNOWN(edges != nullptr); - } - - CPPADCG_ASSERT_UNKNOWN(!edges->arguments.empty()); - - //if(edges->arguments.size() > 2) { - // continue; // should not use this??? - //} - - // flip paths[0] so that it starts at bifurcation - std::reverse(paths[0].begin(), paths[0].end()); - - if (edges->arguments.size() == 1) { - // there is only one path (there are no bifurcations) - return paths; - } - - // there is another path up to target - paths.resize(2); - paths[1].reserve(20); // path up - - /** - * go up - */ - // use the other argument to go up - auto* n1 = paths[0][1].node; - size_t argIndex1 = n->getArguments()[edges->arguments[0]].getOperation() == n1? edges->arguments[1]: edges->arguments[0]; - paths[1].push_back(OperationPathNode(n, argIndex1)); // start at the same location (but different argument index) - - n = n->getArguments()[argIndex1].getOperation(); - - edges = find(*n); - CPPADCG_ASSERT_UNKNOWN(edges != nullptr); // must exist - - while (!edges->arguments.empty()) { - argIndex1 = *edges->arguments.begin(); // ignore other arguments for now!!!! - paths[1].push_back(OperationPathNode(n, argIndex1)); - - n = n->getArguments()[argIndex1].getOperation(); - edges = find(*n); - CPPADCG_ASSERT_UNKNOWN(edges != nullptr); // must exist - } - - paths[1].push_back(OperationPathNode(n, -1)); - - bifIndex = 0; - - break; - } - } -#endif - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/cg.hpp b/ct_core/include/ct/external/cppad/cg/cg.hpp deleted file mode 100644 index fd77d2dba..000000000 --- a/ct_core/include/ct/external/cppad/cg/cg.hpp +++ /dev/null @@ -1,343 +0,0 @@ -#ifndef CPPAD_CG_CG_INCLUDED -#define CPPAD_CG_CG_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * The base data type used to create models. - * It can represent either the result of a symbolic operation or a constant - * parameter value. - * - * @author Joao Leal - */ -template -class CG { -private: - /** - * A node which represents the result from an operation. - * It must be defined for variables and null for parameters. - */ - OperationNode* node_; - /** - * A constant value which must be defined for parameters. - * Its definition is optional for variables. - */ - Base* value_; - -public: - /** - * Default constructor (creates a parameter with a zero value) - */ - inline CG(); - - /** - * Creates a variable resulting from the evaluation this node - * - * @param node The operation node. - */ - inline CG(OperationNode& node); - - /** - * Copy constructor - */ - inline CG(const CG& orig); - - /** - * Assignment operator - */ - inline CG& operator=(const CG& rhs); - - /** - * Creates a parameter with the provided value - * - * @param val The parameter value - */ - inline CG(const Base& val); - - /** - * Assignment operator to a parameter value - * - * @param rhs The parameter value - */ - inline CG& operator=(const Base& rhs); - - /** - * @return The code handler that owns the OperationNode when it is a - * variable, null when it is a parameter. - */ - inline CodeHandler* getCodeHandler() const; - - // variable classification methods - /** - * Determines if it represents the result from a symbolic operation - * which is registered in operation graph of a CodeHandler. - * - * @return true if it represents the result from a symbolic operation - */ - inline bool isVariable() const; - - /** - * Determines if it a constant parameter which is not the result of - * a symbolic operation. - * - * @return true if it represents a constant parameter. - */ - inline bool isParameter() const; - - /** - * Determines if there is value defined. - * Parameters must have a value defined while variable can optionally - * define it. - * - * @return true if there is a value defined - */ - inline bool isValueDefined() const; - - /** - * Provides the current numerical value - * - * @throws CGException if a value is not defined - */ - inline const Base& getValue() const; - - /** - * Defines a value which can alter the resulting model if this object is - * a parameter used as an argument to symbolic operations. - * Variables can also optionally define a value however there will be - * no impact in the resulting model. - */ - inline void setValue(const Base& val); - - inline bool isIdenticalZero() const; - inline bool isIdenticalOne() const; - - inline OperationNode* getOperationNode() const; - - // computed assignment operators - inline CG& operator+=(const CG& right); - inline CG& operator-=(const CG& right); - inline CG& operator*=(const CG& right); - inline CG& operator/=(const CG& right); - inline CG& operator+=(const Base& right); - inline CG& operator-=(const Base& right); - inline CG& operator*=(const Base& right); - inline CG& operator/=(const Base& right); - - template< class T> - inline CG& operator+=(const T &right); - template - inline CG& operator-=(const T &right); - template - inline CG& operator/=(const T &right); - template - inline CG& operator*=(const T &right); - - // unary operators - inline CG operator+() const; - inline CG operator-() const; - - // creating an argument out of this node - inline Argument argument() const; - - - // destructor - virtual ~CG(); -protected: - /** - * Creates a variable/parameter from an existing argument - * - * @param arg An argument that may be a parameter or a variable. - * (the node is assumed to already be managed by the handler) - */ - inline CG(const Argument& arg); - - // - inline void makeParameter(const Base& b); - - inline void makeVariable(OperationNode& operation); - - inline void makeVariable(OperationNode& operation, - std::unique_ptr& value); - - /*************************************************************************** - * friends - **************************************************************************/ - - friend class CodeHandler; - friend class CGAbstractAtomicFun; - friend class Loop; - friend class LoopModel; - - /** - * arithmetic binary operators - */ - friend CG CppAD::cg::operator+ (const CG& left, const CG& right); - friend CG CppAD::cg::operator- (const CG& left, const CG& right); - friend CG CppAD::cg::operator* (const CG& left, const CG& right); - friend CG CppAD::cg::operator/ (const CG& left, const CG& right); - - /** - * comparison operators are not used to create code - */ - friend bool operator< (const CG& left, const CG& right); - friend bool operator<= (const CG& left, const CG& right); - friend bool operator> (const CG& left, const CG& right); - friend bool operator>= (const CG& left, const CG& right); - friend bool operator== (const CG& left, const CG& right); - friend bool operator!= (const CG& left, const CG& right); - - // comparison with double (required by CppAD SparseHessian) - friend bool operator!= (const CG& left, double right); - - /** - * order determining functions - */ - friend bool GreaterThanZero (const CG& x); - friend bool GreaterThanOrZero (const CG& x); - friend bool LessThanZero (const CG& x); - friend bool LessThanOrZero (const CG& x); - friend bool abs_geq (const CG& x, const CG& y); - - // EqualOpSeq function - friend bool EqualOpSeq (const CG& u, const CG& v); - - // NearEqual function - friend bool NearEqual (const CG& x, const CG& y, const Base& r, const Base& a); - friend bool NearEqual (const Base& x, const CG& y, const Base& r, const Base& a); - friend bool NearEqual (const CG& x, const Base& y, const Base& r, const Base& a); - - // CondExp function - friend CG CondExp(CGOpCode op, - const CG& left, - const CG& right, - const CG& trueCase, - const CG& falseCase, - bool (*compare)(const Base&, const Base&)); - - friend CG sign(const CG& x); - - /** - * math functions - */ - friend CG pow(const CG &x, const CG &y); - friend CG abs(const CG& var); - friend CG acos(const CG& var); - friend CG asin(const CG& var); - friend CG atan(const CG& var); - friend CG cos(const CG& var); - friend CG cosh(const CG& var); - friend CG exp(const CG& var); - friend CG log(const CG& var); - friend CG sin(const CG& var); - friend CG sinh(const CG& var); - friend CG sqrt(const CG& var); - friend CG tan(const CG& var); - friend CG tanh(const CG& var); - -#if CPPAD_USE_CPLUSPLUS_2011 - // c++11 functions - friend CG erf(const CG& var); // error function - friend CG asinh(const CG& var); // inverse hyperbolic sin - friend CG acosh(const CG& var); // inverse hyperbolic cosine - friend CG atanh(const CG& var); // inverse hyperbolic tangent - friend CG expm1(const CG& var); // exponential of x minus one - friend CG log1p(const CG& var); // logarithm of one plus x -#endif -}; - - -/** - * Overrides the default behaviour of operator<<(std::ostream& os, const CG& c). - * It can be used recover OperationNode names. - * - * @todo replace this struct with a template variable once C++14 is used - */ -template -struct CGOStreamFunc { - static thread_local std::function&)> FUNC; -}; - -template -thread_local std::function&)> CGOStreamFunc::FUNC = nullptr; - -/** - * Output stream operator for CG objects. - * Default behavior can be overridden using CGOStreamFunc::FUN. - */ -template -inline std::ostream& operator<<( - std::ostream& os, //< stream to write to - const CG& v//< vector that is output - ) { - if(CGOStreamFunc::FUNC != nullptr) { - return CGOStreamFunc::FUNC(os, v); - } - - if (v.isParameter()) { - os << v.getValue(); - } else { - os << *v.getOperationNode(); - if (v.isValueDefined()) { - os << " (" << v.getValue() << ")"; - } - } - return os; -} - -template -inline std::ostringstream& operator<<( - std::ostringstream& os, //< steam to write the vector to - const CG& v//< vector that is output - ) { - if (v.isParameter()) { - os << v.getValue(); - } else { - os << *v.getOperationNode(); - if (v.isValueDefined()) { - os << " (" << v.getValue() << ")"; - } - } - return os; -} - -template -inline std::istream& operator>>( - std::istream& is, //< stream to load a parameter value - CG& v//< the variable that will be assign the value - ) { - Base value; - is >> value; - v = value; - return is; -} - -} // END cg namespace - -template -int Integer(const CppAD::cg::CG& x) { - if (x.isValueDefined()) { - return Integer(x.getValue()); - } else { - CppAD::ErrorHandler::Call(false, __LINE__, __FILE__, "Integer()", "No value defined"); - return 0; - } -} - -} // END CppAD namespace - -#endif diff --git a/ct_core/include/ct/external/cppad/cg/code_handler.hpp b/ct_core/include/ct/external/cppad/cg/code_handler.hpp deleted file mode 100644 index 2c2569433..000000000 --- a/ct_core/include/ct/external/cppad/cg/code_handler.hpp +++ /dev/null @@ -1,880 +0,0 @@ -#ifndef CPPAD_CG_CODE_HANDLER_INCLUDED -#define CPPAD_CG_CODE_HANDLER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Helper class to analyze the operation graph and generate source code - * for several languages - * - * @author Joao Leal - */ -template -class CodeHandler { - friend class CodeHandlerVectorSync; -public: - typedef OperationPathNode PathNode; - typedef std::vector SourceCodePath; - typedef std::vector > ScopePath; - typedef OperationNode Node; - typedef Argument Arg; - typedef CG CGB; - typedef unsigned short ScopeIDType; -protected: - struct LoopData; // forward declaration - -protected: - // counter used to determine visitation IDs for the operation tree - size_t _idVisit; - // counter used to generate variable IDs - size_t _idCount; - // counter used to generate array variable IDs - size_t _idArrayCount; - // counter used to generate sparse array variable IDs - size_t _idSparseArrayCount; - // counter used to generate IDs for atomic functions - size_t _idAtomicCount; - // the independent variables - std::vector _independentVariables; - // the current dependent variables - ArrayWrapper* _dependents; - /** - * nodes managed by this code handler which include all - * all OperationNodes created by CG objects - */ - std::vector _codeBlocks; - /** - * All CodeHandlerVector associated with this code handler - */ - std::set*> _managedVectors; - /** - * the ID of the last visit to each managed node - */ - CodeHandlerVector _lastVisit; - /** - * scope of each managed operation node - */ - CodeHandlerVector _scope; - /** - * evaluation order of each managed node - * (zero means that an evaluation position was never assigned) - */ - CodeHandlerVector _evaluationOrder; - /** - * the last index in the evaluation order for which an operation node - * is taken as an argument of another operation node. - * (zero means that the node was never used) - */ - CodeHandlerVector _lastUsageOrder; - /** - * the total number of times the result of an operation node is used - */ - CodeHandlerVector _totalUseCount; - /** - * Provides the variable ID that was altered/assigned to operation nodes. - * Zero means that no variable is assigned. - */ - CodeHandlerVector _varId; - /** - * the order for the variable creation in the source code - */ - std::vector _variableOrder; - /** - * maps dependencies between variables in _variableOrder - */ - std::vector> _variableDependencies; - /** - * the order for the variable creation in the source code - * (each level represents a different variable scope) - */ - std::vector > _scopedVariableOrder; - /** - * - */ - LoopData _loops; - /** - * maps the IDs of the atomic functions - */ - std::map*> _atomicFunctions; - /** - * already used atomic function names (may contain names which were - * used by previous calls to this/other CondeHandlers) - */ - std::map _atomicFunctionName2Index; - /** - * the order of the atomic functions (may contain names which were - * used by previous calls to this/other CondeHandlers) - */ - std::vector* _atomicFunctionsOrder; - /** - * - */ - std::map _atomicFunctionId2Index; - /** - * the maximum forward mode order each atomic function is called - * (-1 means forward mode not used) - */ - std::vector _atomicFunctionsMaxForward; - /** - * the maximum reverse mode order each atomic function is called - * (-1 means reverse mode not used) - */ - std::vector _atomicFunctionsMaxReverse; - // a flag indicating if this handler was previously used to generate code - bool _used; - // a flag indicating whether or not to reuse the IDs of destroyed variables - bool _reuseIDs; - // scope color/index counter - ScopeIDType _scopeColorCount; - // the current scope color/index counter - ScopeIDType _currentScopeColor; - // all scopes - std::vector _scopes; - // possible altered nodes due to scope conditionals (altered node <-> clone of original) - std::list > _alteredNodes; - // the language used for source code generation - Language* _lang; - /** - * information sent to the language - */ - std::unique_ptr > _info; - // the lowest ID used for temporary variables - size_t _minTemporaryVarID; - /** - * whether or not the dependent variables should be zeroed before - * executing the operation graph - */ - bool _zeroDependents; - // - bool _verbose; - /** - * used to track evaluation times and print out messages - */ - JobTimer* _jobTimer; - /** - * Auxiliary index declaration (might not be used) - */ - Node* _auxIndexI; - /** - * Auxiliary index (might not be used) - */ - IndexOperationNode* _auxIterationIndexOp; -public: - - CodeHandler(size_t varCount = 50); - - CodeHandler(const CodeHandler&) = delete; - - CodeHandler& operator=(const CodeHandler&) = delete; - - /** - * Destructor - */ - inline virtual ~CodeHandler(); - - /** - * Defines whether or not to reuse the node IDs once they are not need by - * a node anymore. - */ - inline void setReuseVariableIDs(bool reuse); - - /** - * Whether or not node IDs are reused once they are not need by a node - * anymore. - */ - inline bool isReuseVariableIDs() const; - - template - inline void makeVariables(VectorCG& variables) { - for (size_t i = 0; i < variables.size(); i++) { - makeVariable(variables[i]); - } - } - - inline void makeVariables(std::vector >& variables); - - inline void makeVariable(AD& variable); - - inline void makeVariable(CGB& variable); - - /** - * The number of independent variables defined with makeVariable(). - */ - size_t getIndependentVariableSize() const; - - /** - * @throws CGException if a variable is not found in the independent vector - */ - size_t getIndependentVariableIndex(const Node& var) const; - - /** - * Provides variable IDs that were assigned to operation nodes. - * Zero means that no variable is assigned. - * The first IDs are reserved for the independent variables. - * It can be an empty vector if IDs have not yet been assigned. - */ - inline const CodeHandlerVector& getVariablesIDs() const; - - inline size_t getMaximumVariableID() const; - - inline bool isVerbose() const; - - inline void setVerbose(bool verbose); - - inline JobTimer* getJobTimer() const; - - inline void setJobTimer(JobTimer* jobTimer); - - /** - * Determines whether or not the dependent variables will be set to zero - * before executing the operation graph - * - * @return true if the dependents will be zeroed - */ - inline bool isZeroDependents() const; - - /** - * Defines whether or not the dependent variables should be set to zero - * before executing the operation graph - * - * @param true if the dependents should be zeroed - */ - inline void setZeroDependents(bool zeroDependents); - - inline size_t getOperationTreeVisitId() const; - - inline void startNewOperationTreeVisit(); - - inline bool isVisited(const Node& node) const; - - inline void markVisited(const Node& node); - - /** - * Provides the name used by an atomic function with a given ID. - * - * @param id the atomic function ID. - * @return a pointer to the atomic function name if it was registered - * or nullptr otherwise - */ - inline const std::string* getAtomicFunctionName(size_t id) const; - - /** - * Provides a map with all the currently registered atomic functions. - * - * @return a map with the atomic function ID as key and the atomic - * function as value - */ - inline const std::map* >& getAtomicFunctions() const; - - /** - * Provides the maximum forward mode order used by all atomic functions - * in the last call to ::generateCode - * (-1 means forward mode not used). - */ - const std::vector& getExternalFuncMaxForwardOrder() const; - - /** - * Provides the maximum reverse mode order used by all atomic functions - * in the last call to ::generateCode - * (-1 means forward mode not used). - */ - const std::vector& getExternalFuncMaxReverseOrder() const; - - /** - * Provides the name used by a loop atomic function with a given ID. - * - * @param id the atomic function ID. - * @return a pointer to the atomic loop function name if it was - * registered or nullptr otherwise - */ - inline const std::string* getLoopName(size_t id) const; - - inline const std::vector& getScopes() const; - - /************************************************************************** - * Graph management functions - *************************************************************************/ - /** - * Finds occurrences of a source code fragment in an operation graph. - * - * @param root the operation graph where to search - * @param target the source code fragment to find in root - * @param max the maximum number of occurrences of code to find in root - * @return the paths from root to code - */ - inline std::vector findPaths(Node& root, - Node& target, - size_t max); - - inline BidirGraph findPathGraph(Node& root, - Node& target) ; - - inline BidirGraph findPathGraph(Node& root, - Node& target, - size_t& bifurcations, - size_t maxBifurcations = std::numeric_limits::max()); - - /************************************************************************** - * Source code generation - *************************************************************************/ - - /** - * Creates the source code from the operations registered so far. - * - * @param out The output stream where the source code is to be printed. - * @param lang The targeted language. - * @param dependent The dependent variables for which the source code - * should be generated. By defining this vector the - * number of operations in the source code can be - * reduced and thus providing a more optimized code. - * @param nameGen Provides the rules for variable name creation. - */ - virtual void generateCode(std::ostream& out, - Language& lang, - CppAD::vector& dependent, - VariableNameGenerator& nameGen, - const std::string& jobName = "source"); - - virtual void generateCode(std::ostream& out, - Language& lang, - std::vector& dependent, - VariableNameGenerator& nameGen, - const std::string& jobName = "source"); - - virtual void generateCode(std::ostream& out, - Language& lang, - ArrayWrapper& dependent, - VariableNameGenerator& nameGen, - const std::string& jobName = "source"); - - /** - * Creates the source code from the operations registered so far. - * - * @param out The output stream where the source code is to be printed. - * @param lang The targeted language. - * @param dependent The dependent variables for which the source code - * should be generated. By defining this vector the - * number of operations in the source code can be - * reduced and thus providing a more optimized code. - * @param nameGen Provides the rules for variable name creation. - * @param atomicFunctions The order of the atomic functions. - */ - virtual void generateCode(std::ostream& out, - Language& lang, - CppAD::vector& dependent, - VariableNameGenerator& nameGen, - std::vector& atomicFunctions, - const std::string& jobName = "source"); - - virtual void generateCode(std::ostream& out, - Language& lang, - std::vector& dependent, - VariableNameGenerator& nameGen, - std::vector& atomicFunctions, - const std::string& jobName = "source"); - - virtual void generateCode(std::ostream& out, - Language& lang, - ArrayWrapper& dependent, - VariableNameGenerator& nameGen, - std::vector& atomicFunctions, - const std::string& jobName = "source"); - - size_t getTemporaryVariableCount() const; - - size_t getTemporaryArraySize() const; - - size_t getTemporarySparseArraySize() const; - - /************************************************************************** - * Reusing handler and nodes - *************************************************************************/ - - /** - * Resets this handler for a usage with completely different nodes. - * @warning all managed memory will be deleted - */ - virtual void reset(); - - /** - * Resets the previously used dependents and their children so that they - * can be reused again by this handler. - */ - inline void resetNodes(); - - /************************************************************************** - * access to managed memory - *************************************************************************/ - - /** - * Creates a shallow clone of an operation node - */ - inline Node* cloneNode(const Node& n); - - inline Node* makeNode(CGOpCode op); - - inline Node* makeNode(CGOpCode op, - const Arg& arg); - - inline Node* makeNode(CGOpCode op, - std::vector&& args); - - inline Node* makeNode(CGOpCode op, - std::vector&& info, - std::vector&& args); - - inline Node* makeNode(CGOpCode op, - const std::vector& info, - const std::vector& args); - - inline LoopStartOperationNode* makeLoopStartNode(Node& indexDcl, - size_t iterationCount); - - inline LoopStartOperationNode* makeLoopStartNode(Node& indexDcl, - IndexOperationNode& iterCount); - - inline LoopEndOperationNode* makeLoopEndNode(LoopStartOperationNode& loopStart, - const std::vector& endArgs); - - inline PrintOperationNode* makePrintNode(const std::string& before, - const Arg& arg, - const std::string& after); - - inline IndexOperationNode* makeIndexNode(Node& indexDcl); - - inline IndexOperationNode* makeIndexNode(LoopStartOperationNode& loopStart); - - inline IndexOperationNode* makeIndexNode(IndexAssignOperationNode& indexAssign); - - inline IndexAssignOperationNode* makeIndexAssignNode(Node& index, - IndexPattern& indexPattern, - IndexOperationNode& index1); - - inline IndexAssignOperationNode* makeIndexAssignNode(Node& index, - IndexPattern& indexPattern, - IndexOperationNode* index1, - IndexOperationNode* index2); - - inline Node* makeIndexDclrNode(const std::string& name); - - /** - * Provides the current number of OperationNodes created by the model. - * This number is not the total number of operations in the final - * model since it also contains Operations nodes marking - * independent variables and there could be unused operations by - * the model (dead-code). - * @return The number of OperationNodes created by the model. - */ - inline size_t getManagedNodesCount() const; - - /** - * Provides the OperationNodes created by the model. - */ - inline const std::vector& getManagedNodes() const; - - /** - * Allows to delete OperationNodes that are managed internally. - * @warning: This is a dangerous method, make sure these nodes are not used - * anywhere else! - * @param start The index of the first OperationNode to be deleted - * @param end The index after the last OperationNode to be deleted - */ - inline void deleteManagedNodes(size_t start, - size_t end); - - /************************************************************************** - * Value generation - *************************************************************************/ - CGB createCG(const Arg& arg); - - /************************************************************************** - * Loop management - *************************************************************************/ - - const std::map*>& getLoops() const; - - inline LoopModel* getLoop(size_t loopId) const; - - inline size_t addLoopDependentIndexPattern(IndexPattern& jacPattern); - - inline void manageLoopDependentIndexPattern(const IndexPattern* pattern); - - inline size_t addLoopIndependentIndexPattern(IndexPattern& pattern, size_t hint); - - /*********************************************************************** - * Index patterns - **********************************************************************/ - static inline void findRandomIndexPatterns(IndexPattern* ip, - std::set& found); - - /************************************************************************** - * Operation graph manipulation - *************************************************************************/ - - /** - * Solves an expression (e.g. f(x, y) == 0) for a given variable (e.g. x). - * - * @param expression The original expression (f(x, y)) - * @param var The variable to solve for - * @return The expression for the variable - * @throws CGException if it is not possible to solve the expression - */ - inline CGB solveFor(Node& expression, - Node& var); - - inline bool isSolvable(Node& expression, - Node& var); - - /** - * Eliminates an independent variable by substitution using the provided - * dependent variable which is assumed to be a residual of an equation. - * If successful the model will contain one less independent variable. - * - * @param indep The independent variable to eliminate. - * @param dep The dependent variable representing a residual - * @param removeFromIndeps Whether or not to immediately remove the - * independent variable from the list of - * independents in the model. The substitution - * operation can only be reversed if the - * variable is not removed. - * @throws CGException if the dependent variable does not belong to this handler - */ - inline void substituteIndependent(const CGB& indep, - const CGB& dep, - bool removeFromIndeps = true); - - inline void substituteIndependent(Node& indep, - Node& dep, - bool removeFromIndeps = true); - - /** - * Reverts a substitution of an independent variable that has not been - * removed from the list of independents yet. - * Warning: it does not recover any custom name assigned to the variable. - * - * @param indep The independent variable - * @throws CGException if the dependent variable does not belong to this handler - */ - inline void undoSubstituteIndependent(Node& indep); - - /** - * Finalizes the substitution of an independent variable by eliminating - * it from the list of independents. After this operation the variable - * substitution cannot be undone. - * - * @param indep The independent variable - * @throws CGException if the dependent variable is not an not an alias or it does not belong to this handler - */ - inline void removeIndependent(Node& indep); - - /** - * Adds an operation node to the list of nodes to be deleted when this - * handler is destroyed. - * - * @param code The operation node to be managed. - * @return true if the node was successfully added to the list or - * false if it had already been previously added. - */ - inline bool manageOperationNodeMemory(Node* code); - -protected: - - virtual Node* manageOperationNode(Node* code); - - inline void addVector(CodeHandlerVectorSync* v); - - inline void removeVector(CodeHandlerVectorSync* v); - - virtual void markCodeBlockUsed(Node& code); - - inline bool handleTemporaryVarInDiffScopes(Node& code, - size_t oldScope, size_t newScope); - - inline void replaceWithConditionalTempVar(Node& tmp, - IndexOperationNode& iterationIndexOp, - const std::vector& iterationRegions, - ScopeIDType oldScope, - ScopeIDType commonScopeColor); - - inline void updateTemporaryVarInDiffScopes(Node& code); - - inline void restoreTemporaryVar(Node& tmp); - - inline void restoreTemporaryVar(Node* tmp, - Node* opClone); - - inline void updateVarScopeUsage(Node* node, - ScopeIDType usageScope, - ScopeIDType oldUsageScope); - - inline void addScopeToVarOrder(size_t scope, - size_t& e); - - /** - * Determines the depth of the first different scope from scope paths of - * two scopes - * - * @param color1 scope color 1 - * @param color2 scope color 2 - * @return the depth of the first different scope - */ - inline size_t findFirstDifferentScope(size_t color1, - size_t color2); - - /** - * Attempt to reduce the number of ifs when there are consecutive ifs with - * the same condition - */ - inline void optimizeIfs(); - - inline void replaceScope(Node* node, - ScopeIDType oldScope, - ScopeIDType newScope); - - /** - * Removes cyclic dependencies when 'ifs' are merged together. - * Relative variable order must have already been defined. - * - * @param node the node being visited - * @param scope the scope where the cyclic dependency could appear (or scopes inside it) - * @param endIf the dependency to remove - */ - inline void breakCyclicDependency(Node* node, - size_t scope, - Node* endIf); - - inline bool containedInScope(const Node& node, - ScopeIDType scope); - - inline static bool containsArgument(const Node& node, - const Node& arg); - - virtual void registerAtomicFunction(CGAbstractAtomicFun& atomic); - - /*********************************************************************** - * - **********************************************************************/ - virtual void checkVariableCreation(Node& code); - - inline void addToEvaluationQueue(Node& arg); - - inline void reduceTemporaryVariables(ArrayWrapper& dependent); - - /** - * Change operation order so that the total number of temporary variables is - * reduced. - * @param dependent The vector of dependent variable values - */ - inline void reorderOperations(ArrayWrapper& dependent); - - inline void reorderOperation(Node& node); - - /** - * Determine the highest location in the evaluation queue of temporary - * variables used by an operation node in the same scope. - * @return the highest location of the temporary variables or - * the location of node itself if it doesn't use any temporary - * variable (in the same scope) - */ - inline size_t findLastTemporaryLocation(Node& node); - - inline void repositionEvaluationQueue(size_t fromPos, - size_t toPos); - - /** - * Determines when each temporary variable is last used in the - * evaluation order - * - * @param node The current node for which the number of usages is to be to determined - */ - inline void determineLastTempVarUsage(Node& node); - - /** - * Determines relations between variables with an ID - */ - inline void findVariableDependencies(); - - inline void findVariableDependencies(size_t i, - Node& node); - - /** - * Defines the evaluation order for the code fragments that do not - * create variables (right hand side variables) - * @param code The operation just added to the evaluation order - */ - inline void dependentAdded2EvaluationQueue(Node& node); - - inline void updateEvaluationQueueOrder(Node& node, - size_t newEvalOrder); - - inline bool isIndependent(const Node& arg) const; - - inline bool isTemporary(const Node& arg) const; - - inline static bool isTemporaryArray(const Node& arg); - - inline static bool isTemporarySparseArray(const Node& arg); - - inline static Node* getOperationFromAlias(Node& alias); - - inline size_t getEvaluationOrder(const Node& node) const; - - inline void setEvaluationOrder(Node& node, - size_t order); - - inline size_t getLastUsageEvaluationOrder(const Node& node) const; - - inline void setLastUsageEvaluationOrder(const Node& node, - size_t last); - - /** - * Provides the total number of times the result of an operation node is - * being used as an argument for another operation. - * @return the total usage count - */ - inline size_t getTotalUsageCount(const Node& node) const; - - inline void setTotalUsageCount(const Node& node, - size_t cout); - - inline void increaseTotalUsageCount(const Node& node); - - inline void resetManagedNodes(); - - /************************************************************************** - * Graph management functions - *************************************************************************/ - - inline void findPaths(SourceCodePath& path2node, - Node& code, - std::vector& found, - size_t max); - - static inline std::vector findPathsFromNode(const std::vector nodePaths, - Node& node); - - /************************************************************************** - * Operation graph manipulation - *************************************************************************/ - /** - * Solves an expression (e.g. f(x, y) == 0) for a given variable (e.g. x) - * The variable can appear only once in the expression. - * This is also known as isolation. - * - * @param path The path from the equation residual to the variable - * @return The expression for the variable - * @throws CGException if it is not possible to solve the expression - */ - inline CGB solveFor(const SourceCodePath& path); - - /** - * Reduces the number of occurrences of a variable in an equation. - * For instance: - * f(x,y) = x + y + x - * could become - * f(x,y) = 2 * x + y - * - * @param expression The original expression (f(x, y)) - * @param path1 A path from the equation residual to where the variable - * is used. - * @param path2 A different path from the equation residual to where the - * variable is used. - * @return The new expression for the equation - * @throws CGException if it is not possible to combine the multiple - * occurrences of the variable - */ - inline CGB collectVariable(Node& expression, - const SourceCodePath& path1, - const SourceCodePath& path2, - size_t bifPos); - - inline CGB collectVariableAddSub(const SourceCodePath& pathLeft, - const SourceCodePath& pathRight); - - inline bool isCollectableVariableAddSub(const SourceCodePath& pathLeft, - const SourceCodePath& pathRight, - bool throwEx); - - inline bool isSolvable(const SourceCodePath& path) const; - - /************************************************************************** - * Loop related structure/methods - *************************************************************************/ - struct LoopData { - // maps the loop ids of the loop atomic functions - std::map*> loopModels; - std::vector*> endNodes; - // the used indexes - std::set indexes; - // the used random index patterns - std::set indexRandomPatterns; - // - std::vector dependentIndexPatterns; - std::vector dependentIndexPatternManaged; // garbage collection - std::vector independentIndexPatterns; - // variables used inside a loop which are assigned outside (for different loop depths) - std::vector > outerVars; - // the current loop depth (-1 means no loop) - int depth; - // the evaluation order of the loop start for each loop depth - std::vector startEvalOrder; - - inline LoopData() : - depth(-1) { - } - - inline void prepare4NewSourceGen(); - - inline void reset(); - - /** - * Provides the name used by a loop atomic function with a given ID. - * - * @param id the atomic function ID. - * @return a pointer to the atomic loop function name if it was - * registered, nullptr otherwise - */ - inline const std::string* getLoopName(size_t id) const; - - inline void registerModel(LoopModel& loop); - - inline LoopModel* getLoop(size_t loopId) const; - - size_t addDependentIndexPattern(IndexPattern& jacPattern); - - void manageDependentIndexPattern(const IndexPattern* pattern); - - size_t addIndependentIndexPattern(IndexPattern& pattern, size_t hint); - - void addLoopEndNode(Node& node); - }; - - /************************************************************************** - * friends - *************************************************************************/ - friend class CG; - friend class CGAbstractAtomicFun; - friend class BaseAbstractAtomicFun; - friend class LoopModel; - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif diff --git a/ct_core/include/ct/external/cppad/cg/code_handler_impl.hpp b/ct_core/include/ct/external/cppad/cg/code_handler_impl.hpp deleted file mode 100644 index 4f47bd2b8..000000000 --- a/ct_core/include/ct/external/cppad/cg/code_handler_impl.hpp +++ /dev/null @@ -1,2039 +0,0 @@ -#ifndef CPPAD_CG_CODE_HANDLER_IMPL_INCLUDED -#define CPPAD_CG_CODE_HANDLER_IMPL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -CodeHandler::CodeHandler(size_t varCount) : - _idVisit(1), - _idCount(1), - _idArrayCount(1), - _idSparseArrayCount(1), - _idAtomicCount(1), - _dependents(nullptr), - _lastVisit(*this), - _scope(*this), - _evaluationOrder(*this), - _lastUsageOrder(*this), - _totalUseCount(*this), - _varId(*this), - _scopedVariableOrder(1), - _atomicFunctionsOrder(nullptr), - _used(false), - _reuseIDs(true), - _scopeColorCount(0), - _currentScopeColor(0), - _lang(nullptr), - _minTemporaryVarID(0), - _zeroDependents(false), - _verbose(false), - _jobTimer(nullptr) { - _codeBlocks.reserve(varCount); - //_variableOrder.reserve(1 + varCount / 3); - _scopedVariableOrder[0].reserve(1 + varCount / 3); - - _auxIndexI = makeIndexDclrNode("i"); - _auxIterationIndexOp = makeIndexNode(*_auxIndexI); -} - -template -inline CodeHandler::~CodeHandler() { - reset(); - - for (auto* v : _managedVectors) { - v->handler_ = nullptr; - } -} - -template -inline void CodeHandler::setReuseVariableIDs(bool reuse) { - _reuseIDs = reuse; -} - -template -inline bool CodeHandler::isReuseVariableIDs() const { - return _reuseIDs; -} - -template -inline void CodeHandler::makeVariables(std::vector >& variables) { - for (auto& v : variables) { - makeVariable(v); - } -} - -template -inline void CodeHandler::makeVariable(AD& variable) { - CGB v; - makeVariable(v); // make it a codegen variable - variable = v; // variable id now the same as v -} - -template -inline void CodeHandler::makeVariable(CGB& variable) { - _independentVariables.push_back(makeNode(CGOpCode::Inv)); - variable.makeVariable(*_independentVariables.back()); -} - -template -size_t CodeHandler::getIndependentVariableSize() const { - return _independentVariables.size(); -} - -template -inline const CodeHandlerVector& CodeHandler::getVariablesIDs() const { - return _varId; -} - -template -inline size_t CodeHandler::getMaximumVariableID() const { - return _idCount; -} - -template -inline bool CodeHandler::isVerbose() const { - return _verbose; -} - -template -inline void CodeHandler::setVerbose(bool verbose) { - _verbose = verbose; -} - -template -inline JobTimer* CodeHandler::getJobTimer() const { - return _jobTimer; -} - -template -inline void CodeHandler::setJobTimer(JobTimer* jobTimer) { - _jobTimer = jobTimer; -} - -template -inline bool CodeHandler::isZeroDependents() const { - return _zeroDependents; -} - -template -inline void CodeHandler::setZeroDependents(bool zeroDependents) { - _zeroDependents = zeroDependents; -} - -template -size_t CodeHandler::getIndependentVariableIndex(const Node& var) const { - CPPADCG_ASSERT_UNKNOWN(var.getOperationType() == CGOpCode::Inv); - - typename std::vector::const_iterator it = - std::find(_independentVariables.begin(), _independentVariables.end(), &var); - if (it == _independentVariables.end()) { - throw CGException("Variable not found in the independent variable vector"); - } - - return it - _independentVariables.begin(); -} - -template -inline size_t CodeHandler::getOperationTreeVisitId() const { - return _idVisit; -} - -template -inline void CodeHandler::startNewOperationTreeVisit() { - assert(_idVisit < std::numeric_limits::max()); - - _lastVisit.adjustSize(); - _idVisit++; -} - -template -inline bool CodeHandler::isVisited(const Node& node) const { - size_t p = node.getHandlerPosition(); - return p < _lastVisit.size() && _lastVisit[node] == _idVisit; -} - -template -inline void CodeHandler::markVisited(const Node& node) { - _lastVisit.adjustSize(node); - _lastVisit[node] = _idVisit; -} - -template -inline const std::string* CodeHandler::getAtomicFunctionName(size_t id) const { - typename std::map*>::const_iterator it; - it = _atomicFunctions.find(id); - if (it != _atomicFunctions.end()) - return &(it->second->afun_name()); - else - return nullptr; -} - -template -inline const std::map* >& CodeHandler::getAtomicFunctions() const { - return _atomicFunctions; -} - -template -const std::vector& CodeHandler::getExternalFuncMaxForwardOrder() const { - return _atomicFunctionsMaxForward; -} - -template -const std::vector& CodeHandler::getExternalFuncMaxReverseOrder() const { - return _atomicFunctionsMaxReverse; -} - -template -inline const std::string* CodeHandler::getLoopName(size_t id) const { - return _loops.getLoopName(id); -} - -template -inline const std::vector::ScopePath>& -CodeHandler::getScopes() const { - return _scopes; -} - -template -void CodeHandler::generateCode(std::ostream& out, - Language& lang, - CppAD::vector& dependent, - VariableNameGenerator& nameGen, - const std::string& jobName) { - ArrayWrapper deps(dependent); - generateCode(out, lang, deps, nameGen, jobName); -} - -template -void CodeHandler::generateCode(std::ostream& out, - Language& lang, - std::vector& dependent, - VariableNameGenerator& nameGen, - const std::string& jobName) { - ArrayWrapper deps(dependent); - generateCode(out, lang, deps, nameGen, jobName); -} - -template -void CodeHandler::generateCode(std::ostream& out, - Language& lang, - ArrayWrapper& dependent, - VariableNameGenerator& nameGen, - const std::string& jobName) { - std::vector atomicFunctions; - generateCode(out, lang, dependent, nameGen, atomicFunctions, jobName); -} - -template -void CodeHandler::generateCode(std::ostream& out, - Language& lang, - CppAD::vector& dependent, - VariableNameGenerator& nameGen, - std::vector& atomicFunctions, - const std::string& jobName) { - ArrayWrapper deps(dependent); - generateCode(out, lang, deps, nameGen, atomicFunctions, jobName); -} - -template -void CodeHandler::generateCode(std::ostream& out, - Language& lang, - std::vector& dependent, - VariableNameGenerator& nameGen, - std::vector& atomicFunctions, - const std::string& jobName) { - ArrayWrapper deps(dependent); - generateCode(out, lang, deps, nameGen, atomicFunctions, jobName); -} - -template -void CodeHandler::generateCode(std::ostream& out, - Language& lang, - ArrayWrapper& dependent, - VariableNameGenerator& nameGen, - std::vector& atomicFunctions, - const std::string& jobName) { - using namespace std::chrono; - steady_clock::time_point beginTime; - - if (_jobTimer != nullptr) { - _jobTimer->startingJob("source for '" + jobName + "'"); - } else if (_verbose) { - std::cout << "generating source for '" << jobName << "' ... "; - std::cout.flush(); - beginTime = steady_clock::now(); - } - - _lang = ⟨ - _idCount = 1; - _idArrayCount = 1; - _idSparseArrayCount = 1; - _idAtomicCount = 1; - _dependents = &dependent; - _atomicFunctionsOrder = &atomicFunctions; - _atomicFunctionsMaxForward.resize(atomicFunctions.size()); - _atomicFunctionsMaxReverse.resize(atomicFunctions.size()); - _atomicFunctionName2Index.clear(); - _loops.prepare4NewSourceGen(); - _scopeColorCount = 0; - _currentScopeColor = 0; - _scopes.reserve(4); - _scopes.resize(1); - _alteredNodes.clear(); - _evaluationOrder.adjustSize(); - _lastUsageOrder.adjustSize(); - _totalUseCount.adjustSize(); - _varId.adjustSize(); - _scope.adjustSize(); - - for (size_t i = 0; i < atomicFunctions.size(); i++) { - _atomicFunctionName2Index[atomicFunctions[i]] = i; - } - std::fill(_atomicFunctionsMaxForward.begin(), _atomicFunctionsMaxForward.end(), -1); - std::fill(_atomicFunctionsMaxReverse.begin(), _atomicFunctionsMaxReverse.end(), -1); - - if (_used) { - resetManagedNodes(); - } - _used = true; - - /** - * the first variable IDs are for the independent variables - */ - size_t n = _independentVariables.size(); - for (size_t j = 0; j < n; j++) { - _varId[*_independentVariables[j]] = _idCount++; - } - - size_t m = dependent.size(); - for (size_t i = 0; i < m; i++) { - Node* node = dependent[i].getOperationNode(); - if (node != nullptr && _varId[*node] == 0) { - _varId[*node] = _idCount++; - } - } - - _minTemporaryVarID = _idCount; - - /** - * determine the number of times each variable is used - */ - for (size_t i = 0; i < m; i++) { - Node* node = dependent[i].getOperationNode(); - if (node != nullptr) { - markCodeBlockUsed(*node); - } - } - - /** - * determine the variable creation order - */ - _scopedVariableOrder.reserve(std::max(size_t(1), _scopes.size()) + 10); // some additional scopes might still be added - - startNewOperationTreeVisit(); - - for (size_t i = 0; i < m; i++) { - CGB& var = dependent[i]; - if (var.getOperationNode() != nullptr) { - Node& code = *var.getOperationNode(); - if (!isVisited(code)) { - // dependencies not visited yet - checkVariableCreation(code); - - // make sure new temporary variables are NOT created for - // the independent variables and that a dependency did - // not use it first - if ((_varId[code] == 0 || !isIndependent(code)) && !isVisited(code)) { - addToEvaluationQueue(code); - } - } - markVisited(code); - } - } - - /** - * Generate flat variable order (without scopes) - */ - if (_scopedVariableOrder.size() == 1) { - _variableOrder.swap(_scopedVariableOrder[0]); // most common situation - } else { - optimizeIfs(); // reduce the number of adjoining ifs - - size_t vosize = 0; - for (size_t s = 0; s < _scopedVariableOrder.size(); s++) { - vosize += _scopedVariableOrder[s].size(); - } - _variableOrder.resize(vosize); - - size_t e = 0; - addScopeToVarOrder(0, e); - - // if e > vosize then some nodes (marking the beginning of scopes) - // must have been added more than once - CPPADCG_ASSERT_UNKNOWN(_variableOrder.size() == e); - } - - for (size_t p = 0; p < _variableOrder.size(); p++) { - Node& arg = *_variableOrder[p]; - setEvaluationOrder(arg, p + 1); - dependentAdded2EvaluationQueue(arg); - } - - /** - * Reuse temporary variables - */ - if (_reuseIDs) { - reduceTemporaryVariables(dependent); - } - - /** - * - */ - _variableDependencies.clear(); - if(lang.requiresVariableDependencies()) { - findVariableDependencies(); - } - - nameGen.setTemporaryVariableID(_minTemporaryVarID, _idCount - 1, _idArrayCount - 1, _idSparseArrayCount - 1); - - std::map atomicFunctionName2Id; - typename std::map*>::iterator itA; - for (itA = _atomicFunctions.begin(); itA != _atomicFunctions.end(); ++itA) { - atomicFunctionName2Id[itA->second->afun_name()] = itA->first; - } - - std::map atomicFunctionId2Index; - std::map atomicFunctionId2Name; - for (size_t i = 0; i < _atomicFunctionsOrder->size(); i++) { - const std::string& atomicName = (*_atomicFunctionsOrder)[i]; - std::map::const_iterator it = atomicFunctionName2Id.find(atomicName); - if (it != atomicFunctionName2Id.end()) { - atomicFunctionId2Index[it->second] = i; - atomicFunctionId2Name[it->second] = atomicName; - } - } - - /** - * Creates the source code for a specific language - */ - _info.reset(new LanguageGenerationData(_independentVariables, dependent, - _minTemporaryVarID, _varId, _variableOrder, _variableDependencies, - nameGen, - atomicFunctionId2Index, atomicFunctionId2Name, - _atomicFunctionsMaxForward, _atomicFunctionsMaxReverse, - _reuseIDs, - _loops.indexes, _loops.indexRandomPatterns, - _loops.dependentIndexPatterns, _loops.independentIndexPatterns, - _totalUseCount, _scope, *_auxIterationIndexOp, - _zeroDependents)); - lang.generateSourceCode(out, _info); - - /** - * clean-up - */ - _atomicFunctionName2Index.clear(); - - // restore altered nodes - for (const auto& itAlt : _alteredNodes) { - Node* tmp = itAlt.first; - Node* opClone = itAlt.second; - if (tmp->getOperationType() == CGOpCode::Tmp && !tmp->getInfo().empty()) { // some might have already been restored - tmp->setOperation(opClone->getOperationType(), opClone->getArguments()); - tmp->getInfo() = opClone->getInfo(); - } - } - _alteredNodes.clear(); - - if (_jobTimer != nullptr) { - _jobTimer->finishedJob(); - } else if (_verbose) { - OStreamConfigRestore osr(std::cout); - duration dt = steady_clock::now() - beginTime; - std::cout << "done [" << std::fixed << std::setprecision(3) << dt.count() << "]" << std::endl; - } -} - -template -size_t CodeHandler::getTemporaryVariableCount() const { - if (_idCount == 1) - return 0; // no code generated - else - return _idCount - _minTemporaryVarID; -} - -template -size_t CodeHandler::getTemporaryArraySize() const { - return _idArrayCount - 1; -} - -template -size_t CodeHandler::getTemporarySparseArraySize() const { - return _idSparseArrayCount - 1; -} - -template -void CodeHandler::reset() { - for (Node* n : _codeBlocks) { - delete n; - } - _codeBlocks.clear(); - _independentVariables.clear(); - _idCount = 1; - _idArrayCount = 1; - _idSparseArrayCount = 1; - _idAtomicCount = 1; - - _loops.reset(); - - _used = false; -} - -template -inline void CodeHandler::resetNodes() { - _scope.fill(0); - _evaluationOrder.fill(0); - _lastUsageOrder.fill(0); - _totalUseCount.fill(0); - _varId.fill(0); -} - -/****************************************************************************** -* access to managed memory -******************************************************************************/ - -template -inline OperationNode* CodeHandler::cloneNode(const Node& n) { - return manageOperationNode(new Node(n)); -} - -template -inline OperationNode* CodeHandler::makeNode(CGOpCode op) { - return manageOperationNode(new Node(this, op)); -} - -template -inline OperationNode* CodeHandler::makeNode(CGOpCode op, - const Arg& arg) { - return manageOperationNode(new Node(this, op, arg)); -} - -template -inline OperationNode* CodeHandler::makeNode(CGOpCode op, - std::vector&& args) { - return manageOperationNode(new Node(this, op, std::move(args))); -} - -template -inline OperationNode* CodeHandler::makeNode(CGOpCode op, - std::vector&& info, - std::vector&& args) { - return manageOperationNode(new Node(this, op, std::move(info), std::move(args))); -} - -template -inline OperationNode* CodeHandler::makeNode(CGOpCode op, - const std::vector& info, - const std::vector& args) { - return manageOperationNode(new Node(this, op, info, args)); -} - -template -inline LoopStartOperationNode* CodeHandler::makeLoopStartNode(Node& indexDcl, - size_t iterationCount) { - auto* n = new LoopStartOperationNode(this, indexDcl, iterationCount); - manageOperationNode(n); - return n; -} - -template -inline LoopStartOperationNode* CodeHandler::makeLoopStartNode(Node& indexDcl, - IndexOperationNode& iterCount) { - auto* n = new LoopStartOperationNode(this, indexDcl, iterCount); - manageOperationNode(n); - return n; -} - -template -inline LoopEndOperationNode* CodeHandler::makeLoopEndNode(LoopStartOperationNode& loopStart, - const std::vector& endArgs) { - auto* n = new LoopEndOperationNode(this, loopStart, endArgs); - manageOperationNode(n); - return n; -} - -template -inline PrintOperationNode* CodeHandler::makePrintNode(const std::string& before, - const Arg& arg, - const std::string& after) { - auto* n = new PrintOperationNode(this, before, arg, after); - manageOperationNode(n); - return n; -} - -template -inline IndexOperationNode* CodeHandler::makeIndexNode(Node& indexDcl) { - auto* n = new IndexOperationNode(this, indexDcl); - manageOperationNode(n); - return n; -} - -template -inline IndexOperationNode* CodeHandler::makeIndexNode(LoopStartOperationNode& loopStart) { - auto* n = new IndexOperationNode(this, loopStart); - manageOperationNode(n); - return n; -} - -template -inline IndexOperationNode* CodeHandler::makeIndexNode(IndexAssignOperationNode& indexAssign) { - auto* n = new IndexOperationNode(this, indexAssign); - manageOperationNode(n); - return n; -} - -template -inline IndexAssignOperationNode* CodeHandler::makeIndexAssignNode(Node& index, - IndexPattern& indexPattern, - IndexOperationNode& index1) { - auto* n = new IndexAssignOperationNode(this, index, indexPattern, index1); - manageOperationNode(n); - return n; -} - -template -inline IndexAssignOperationNode* CodeHandler::makeIndexAssignNode(Node& index, - IndexPattern& indexPattern, - IndexOperationNode* index1, - IndexOperationNode* index2) { - auto* n = new IndexAssignOperationNode(this, index, indexPattern, index1, index2); - manageOperationNode(n); - return n; -} - -template -inline OperationNode* CodeHandler::makeIndexDclrNode(const std::string& name) { - CPPADCG_ASSERT_KNOWN(!name.empty(), "index name cannot be empty"); - auto* n = manageOperationNode(new Node(this, CGOpCode::IndexDeclaration)); - n->setName(name); - return n; -} - -template -inline size_t CodeHandler::getManagedNodesCount() const { - return _codeBlocks.size(); -} - -template -inline const std::vector *>& CodeHandler::getManagedNodes() const { - return _codeBlocks; -} - -template -inline void CodeHandler::deleteManagedNodes(size_t start, size_t end) { - if (start >= end) - return; - - start = std::min(start, _codeBlocks.size()); - end = std::min(end, _codeBlocks.size()); - - for (size_t i = start; i < end; ++i) { - delete _codeBlocks[i]; - } - _codeBlocks.erase(_codeBlocks.begin() + start, _codeBlocks.begin() + end); - - // update positions - for (size_t i = start; i < _codeBlocks.size(); ++i) { - _codeBlocks[i]->setHandlerPosition(i); - } - - for (auto* v : _managedVectors) { - v->nodesErased(start, end); - } -} - -/****************************************************************************** - * Value generation - *****************************************************************************/ -template -CG CodeHandler::createCG(const Arg& arg) { - return CGB(arg); -} - -/****************************************************************************** - * Index patterns - *****************************************************************************/ -template -inline void CodeHandler::findRandomIndexPatterns(IndexPattern* ip, - std::set& found) { - if (ip == nullptr) - return; - - if (ip->getType() == IndexPatternType::Random1D || ip->getType() == IndexPatternType::Random2D) { - found.insert(static_cast (ip)); - } else { - std::set indexes; - ip->getSubIndexes(indexes); - for (IndexPattern* sip : indexes) { - if (sip->getType() == IndexPatternType::Random1D || sip->getType() == IndexPatternType::Random2D) - found.insert(static_cast (sip)); - } - } -} - -/************************************************************************** - * Operation graph manipulation - *************************************************************************/ -template -inline bool CodeHandler::manageOperationNodeMemory(Node* code) { - size_t pos = code->getHandlerPosition(); - if (pos >= _codeBlocks.size() || code != _codeBlocks[pos]) { - manageOperationNode(code); - return false; - } - return true; -} - -template -OperationNode* CodeHandler::manageOperationNode(Node* code) { - //CPPADCG_ASSERT_UNKNOWN(std::find(_codeBlocks.begin(), _codeBlocks.end(), code) == _codeBlocks.end()); // <<< too great of an impact in performance - if (_codeBlocks.capacity() == _codeBlocks.size()) { - _codeBlocks.reserve((_codeBlocks.size() * 3) / 2 + 1); - } - - code->setHandlerPosition(_codeBlocks.size()); - _codeBlocks.push_back(code); - return code; -} - -template -inline void CodeHandler::addVector(CodeHandlerVectorSync* v) { - _managedVectors.insert(v); -} - -template -inline void CodeHandler::removeVector(CodeHandlerVectorSync* v) { - _managedVectors.erase(v); -} - -template -void CodeHandler::markCodeBlockUsed(Node& code) { - increaseTotalUsageCount(code); - - CGOpCode op = code.getOperationType(); - if (isIndependent(code)) { - return; // nothing to do - } else if (op == CGOpCode::Alias) { - /** - * Alias operations are always followed so that there is a - * correct usage count at the operation that it points to - */ - CPPADCG_ASSERT_UNKNOWN(code.getArguments().size() == 1); - Node* arg = code.getArguments()[0].getOperation(); - if (arg != nullptr) { - markCodeBlockUsed(*arg); - } - - } else if (getTotalUsageCount(code) == 1) { - // first time this operation is visited - - size_t previousScope = _currentScopeColor; - - _scope[code] = _currentScopeColor; - - // check if there is a scope change - if (op == CGOpCode::LoopStart || op == CGOpCode::StartIf || op == CGOpCode::ElseIf || op == CGOpCode::Else) { - // leaving a scope - ScopePath& sPath = _scopes[_currentScopeColor]; - CPPADCG_ASSERT_UNKNOWN(sPath.back().beginning == nullptr); - if (op == CGOpCode::LoopStart || op == CGOpCode::StartIf) { - sPath.back().beginning = &code; // save the initial node - } else { - CPPADCG_ASSERT_UNKNOWN(!code.getArguments().empty() && - code.getArguments()[0].getOperation() != nullptr && - code.getArguments()[0].getOperation()->getOperationType() == CGOpCode::StartIf); - sPath.back().beginning = code.getArguments()[0].getOperation(); // save the initial node - } - _currentScopeColor = sPath.size() > 1 ? sPath[sPath.size() - 2].color : 0; - } - - if (op == CGOpCode::LoopEnd || op == CGOpCode::EndIf || op == CGOpCode::ElseIf || op == CGOpCode::Else) { - // entering a new scope - _currentScopeColor = ++_scopeColorCount; - - _scopes.resize(_currentScopeColor + 1); - _scopes[_currentScopeColor] = _scopes[previousScope]; - - // change current scope - if (op == CGOpCode::LoopEnd || op == CGOpCode::EndIf) { - // one more scope level - _scopes[_currentScopeColor].push_back(ScopePathElement(_currentScopeColor, &code)); - } else { - // same level but different scope - _scopes[_currentScopeColor].back() = ScopePathElement(_currentScopeColor, &code); - } - - if (op == CGOpCode::LoopEnd) { - _loops.addLoopEndNode(code); - } - } - - /** - * iterate over all arguments - */ - for (const Arg& it : code.getArguments()) { - if (it.getOperation() != nullptr) { - markCodeBlockUsed(*it.getOperation()); - } - } - - if (op == CGOpCode::Index) { - const IndexOperationNode& inode = static_cast&> (code); - // indexes that don't depend on a loop start or an index assignment are declared elsewhere - if (inode.isDefinedLocally()) { - _loops.indexes.insert(&inode.getIndex()); - } - } else if (op == CGOpCode::LoopIndexedIndep || op == CGOpCode::LoopIndexedDep || op == CGOpCode::IndexAssign) { - IndexPattern* ip; - if (op == CGOpCode::LoopIndexedDep) { - size_t pos = code.getInfo()[0]; - ip = _loops.dependentIndexPatterns[pos]; - } else if (op == CGOpCode::LoopIndexedIndep) { - size_t pos = code.getInfo()[1]; - ip = _loops.independentIndexPatterns[pos]; - } else { - ip = &static_cast&> (code).getIndexPattern(); - } - - findRandomIndexPatterns(ip, _loops.indexRandomPatterns); - - } else if (op == CGOpCode::DependentRefRhs) { - CPPADCG_ASSERT_UNKNOWN(code.getInfo().size() == 1); - size_t depIndex = code.getInfo()[0]; - - CPPADCG_ASSERT_UNKNOWN(_dependents->size() > depIndex); - Node* depNode = (*_dependents)[depIndex].getOperationNode(); - CPPADCG_ASSERT_UNKNOWN(depNode != nullptr && depNode->getOperationType() != CGOpCode::Inv); - - _varId[code] = _varId[*depNode]; - } - - /** - * reset scope - */ - if (previousScope != _currentScopeColor) { - _currentScopeColor = previousScope; - } - - } else { - // been to this node before - - if (op == CGOpCode::Tmp && !code.getInfo().empty()) { - /** - * this node was previously altered to ensure that the - * evaluation of the expression is only performed for the - * required iterations - */ - if (_scope[code] == _currentScopeColor) { - // outside an if (defined for all iterations) - restoreTemporaryVar(code); - } else { - updateTemporaryVarInDiffScopes(code); - } - - } else if (_scope[code] != _currentScopeColor && op != CGOpCode::LoopIndexedIndep) { - ScopeIDType oldScope = _scope[code]; - /** - * node previously used in a different scope - * must make sure it is defined before being used in both - * scopes - */ - size_t depth = findFirstDifferentScope(oldScope, _currentScopeColor); - - // update the scope where it should be defined - ScopeIDType newScope; - if (depth == 0) - newScope = 0; - else - newScope = _scopes[_currentScopeColor][depth - 1].color; - - if (oldScope != newScope) { - /** - * does this variable require a condition based on indexes? - */ - bool addedIf = handleTemporaryVarInDiffScopes(code, oldScope, newScope); - - if (!addedIf) { - _scope[code] = newScope; - - /** - * Must also update the scope of the arguments used by this operation - */ - const std::vector& args = code.getArguments(); - size_t aSize = args.size(); - for (size_t a = 0; a < aSize; a++) { - updateVarScopeUsage(args[a].getOperation(), newScope, oldScope); - } - } - } - } - } -} - -template -inline bool CodeHandler::handleTemporaryVarInDiffScopes(Node& code, - size_t oldScope, - size_t newScope) { - if (_currentScopeColor == 0) - return false; - - /** - * @TODO allow Array elements to use a CGTmp instead of a CGArrayCreationOp - */ - CPPADCG_ASSERT_KNOWN(code.getOperationType() != CGOpCode::ArrayCreation, "Not supported yet"); - CPPADCG_ASSERT_KNOWN(code.getOperationType() != CGOpCode::SparseArrayCreation, "Not supported yet"); - - /** - * does this variable require a condition based on indexes? - */ - std::vector iterationRegions; - Node* bScopeNewEnd = _scopes[_currentScopeColor].back().end; - Node* bScopeOldEnd = _scopes[oldScope].back().end; - - CGOpCode bNewOp = bScopeNewEnd->getOperationType(); - CGOpCode bOldOp = bScopeOldEnd->getOperationType(); - - if ((bNewOp == CGOpCode::EndIf || bNewOp == CGOpCode::Else || bNewOp == CGOpCode::ElseIf) && - (bOldOp == CGOpCode::EndIf || bOldOp == CGOpCode::Else || bOldOp == CGOpCode::ElseIf)) { - // used in 2 different if/else branches - - /** - * determine the iterations which use this temporary variable - */ - Node* bScopeNew = bScopeNewEnd->getArguments()[0].getOperation(); - Node* bScopeOld = bScopeOldEnd->getArguments()[0].getOperation(); - - IndexOperationNode* newIterIndexOp = nullptr; - iterationRegions = ifBranchIterationRanges(bScopeNew, newIterIndexOp); - CPPADCG_ASSERT_UNKNOWN(iterationRegions.size() >= 2); - - IndexOperationNode* oldIterIndexOp = nullptr; - std::vector oldIterRegions = ifBranchIterationRanges(bScopeOld, oldIterIndexOp); - combineOverlapingIterationRanges(iterationRegions, oldIterRegions); - CPPADCG_ASSERT_UNKNOWN(iterationRegions.size() >= 2); - CPPADCG_ASSERT_UNKNOWN(newIterIndexOp != nullptr && newIterIndexOp == oldIterIndexOp); - - if (iterationRegions.size() > 2 || - iterationRegions[0] != 0 || - iterationRegions[1] != std::numeric_limits::max()) { - // this temporary variable is not used by all iterations - - replaceWithConditionalTempVar(code, *newIterIndexOp, iterationRegions, oldScope, newScope); - return true; - } - } - - return false; -} - -template -inline void CodeHandler::replaceWithConditionalTempVar(Node& tmp, - IndexOperationNode& iterationIndexOp, - const std::vector& iterationRegions, - ScopeIDType oldScope, - ScopeIDType commonScopeColor) { - /** - * clone - */ - Node* opClone = cloneNode(tmp); - - /** - * Create condition - */ - Node* tmpDclVar = makeNode(CGOpCode::TmpDcl); - Arg tmpArg(*tmpDclVar); - - Node* cond = makeNode(CGOpCode::IndexCondExpr, iterationRegions, {iterationIndexOp}); - - // if - Node* ifStart = makeNode(CGOpCode::StartIf, *cond); - - Node* tmpAssign = makeNode(CGOpCode::LoopIndexedTmp, {tmpArg, *opClone}); - Node* ifAssign = makeNode(CGOpCode::CondResult, {*ifStart, *tmpAssign}); - - // end if - Node* endIf = makeNode(CGOpCode::EndIf, {*ifStart, *ifAssign}); - - /** - * Change original variable - */ - tmp.setOperation(CGOpCode::Tmp, {tmpArg, *endIf}); - tmp.getInfo().resize(1); // used to mark that this node was altered here - - // created new nodes, must adjust vector sizes - _scope.adjustSize(); - _lastVisit.adjustSize(); - _scope.adjustSize(); - _evaluationOrder.adjustSize(); - _lastUsageOrder.adjustSize(); - _totalUseCount.adjustSize(); - _varId.adjustSize(); - - /** - * add the new scope - */ - size_t newScopeColor = ++_scopeColorCount; - _scopes.resize(newScopeColor + 1); - _scopes[newScopeColor] = _scopes[commonScopeColor]; - - // one more scope level - _scopes[newScopeColor].push_back(ScopePathElement(newScopeColor, endIf, ifStart)); - - // apply scope colors - _scope[*tmpDclVar] = commonScopeColor; - _scope[*ifStart] = newScopeColor; - _scope[*cond] = newScopeColor; - _scope[*opClone] = newScopeColor; - _scope[*ifAssign] = newScopeColor; - _scope[*tmpAssign] = newScopeColor; - _scope[*endIf] = commonScopeColor; - _scope[tmp] = commonScopeColor; - - // total usage count - setTotalUsageCount(*tmpDclVar, 1); - setTotalUsageCount(*ifStart, 1); - setTotalUsageCount(*cond, 1); - setTotalUsageCount(*opClone, 1); - setTotalUsageCount(*ifAssign, 1); - setTotalUsageCount(*tmpAssign, 1); - setTotalUsageCount(*endIf, 1); - - /** - * Must also update the scope of the arguments used by this operation - */ - const std::vector& cargs = opClone->getArguments(); - size_t aSize = cargs.size(); - for (size_t a = 0; a < aSize; a++) { - updateVarScopeUsage(cargs[a].getOperation(), newScopeColor, oldScope); - } - - _alteredNodes.push_back(std::make_pair(&tmp, opClone)); -} - -template -inline void CodeHandler::updateTemporaryVarInDiffScopes(Node& code) { - if (_scope[code] != _currentScopeColor) { - return; //nothing to change - } - - /** - * does this variable require a condition based on indexes? - */ - if (_currentScopeColor == 0) - restoreTemporaryVar(code); - - /** - * Determine if it should be moved into a different scope - * so that it is defined before being used in both - * scopes - */ - ScopeIDType oldScope = _scope[code]; - - size_t depth = findFirstDifferentScope(oldScope, _currentScopeColor); - - // update the scope where it should be defined - ScopeIDType newScope = depth == 0 ? 0 : _scopes[_currentScopeColor][depth - 1].color; - - /** - * does this variable require a condition based on indexes? - */ - std::vector iterationRegions; - Node* bScopeNewEnd = _scopes[_currentScopeColor].back().end; - Node* endif = code.getArguments()[0].getOperation(); - CPPADCG_ASSERT_UNKNOWN(endif->getOperationType() == CGOpCode::EndIf); - Node* bScopeOldEnd = _scopes[_scope[*endif]].back().end; - - CGOpCode bNewOp = bScopeNewEnd->getOperationType(); - - if (bNewOp == CGOpCode::EndIf || bNewOp == CGOpCode::Else || bNewOp == CGOpCode::ElseIf) { - // used in 2 different if/else branches - - /** - * determine the iterations which use this temporary variable - */ - Node* bScopeNew = bScopeNewEnd->getArguments()[0].getOperation(); - Node* bScopeOld = bScopeOldEnd->getArguments()[0].getOperation(); - - IndexOperationNode* newIterIndexOp = nullptr; - iterationRegions = ifBranchIterationRanges(bScopeNew, newIterIndexOp); - CPPADCG_ASSERT_UNKNOWN(iterationRegions.size() >= 2); - - IndexOperationNode* oldIterIndexOp = nullptr; - const std::vector oldIterRegions = ifBranchIterationRanges(bScopeOld, oldIterIndexOp); - combineOverlapingIterationRanges(iterationRegions, oldIterRegions); - CPPADCG_ASSERT_UNKNOWN(iterationRegions.size() >= 2); - CPPADCG_ASSERT_UNKNOWN(newIterIndexOp != nullptr && newIterIndexOp == oldIterIndexOp); - - if (iterationRegions.size() == 2 && - (iterationRegions[0] == 0 || - iterationRegions[1] == std::numeric_limits::max())) { - // this temporary variable is used by all iterations - // there is no need for an 'if' - restoreTemporaryVar(code); - - } else if (oldIterRegions != iterationRegions) { - Node* cond = bScopeOld->getArguments()[0].getOperation(); - CPPADCG_ASSERT_UNKNOWN(cond->getOperationType() == CGOpCode::IndexCondExpr); - cond->getInfo() = iterationRegions; - } - - } - - if (oldScope != newScope) { - _scope[code] = newScope; - /** - * Must also update the scope of the arguments used by this operation - */ - const std::vector& cargs = code.getArguments(); - size_t aSize = cargs.size(); - for (size_t a = 0; a < aSize; a++) { - updateVarScopeUsage(cargs[a].getOperation(), newScope, oldScope); - } - } - -} - -template -inline void CodeHandler::restoreTemporaryVar(Node& tmp) { - CPPADCG_ASSERT_UNKNOWN(tmp.getOperationType() == CGOpCode::Tmp && !tmp.getInfo().empty()); - - Node* endIf = tmp.getArguments()[1].getOperation(); - Node* ifAssign = endIf->getArguments()[1].getOperation(); - Node* tmpAssign = ifAssign->getArguments()[1].getOperation(); - Node* opClone = tmpAssign->getArguments()[1].getOperation(); - tmp.setOperation(opClone->getOperationType(), opClone->getArguments()); - tmp.getInfo() = opClone->getInfo(); - - _scope[tmp] = _currentScopeColor; - - /** - * Must also update the scope of the arguments used by this operation - */ - const std::vector& args = tmp.getArguments(); - size_t aSize = args.size(); - for (size_t a = 0; a < aSize; a++) { - updateVarScopeUsage(args[a].getOperation(), _currentScopeColor, _scope[*opClone]); - } -} - -template -inline void CodeHandler::restoreTemporaryVar(Node* tmp, - Node* opClone) { - CPPADCG_ASSERT_UNKNOWN(tmp->getOperationType() == CGOpCode::Tmp && !tmp->getInfo().empty()); - - tmp->setOperation(opClone->getOperationType(), opClone->getArguments()); - tmp->getInfo() = opClone->getInfo(); - - _scope[*tmp] = _currentScopeColor; - - /** - * Must also update the scope of the arguments used by this operation - */ - const std::vector& args = tmp->getArguments(); - size_t aSize = args.size(); - for (size_t a = 0; a < aSize; a++) { - updateVarScopeUsage(args[a].getOperation(), _currentScopeColor, _scope[*opClone]); - } -} - -template -inline void CodeHandler::updateVarScopeUsage(Node* node, - ScopeIDType usageScope, - ScopeIDType oldUsageScope) { - if (node == nullptr || _scope[*node] == usageScope) - return; - - - ScopeIDType oldScope = _scope[*node]; - ScopeIDType newScope; - - if (oldScope == oldUsageScope) { - newScope = usageScope; - } else { - size_t depth = findFirstDifferentScope(oldScope, usageScope); - - newScope = (depth == 0) ? 0 : _scopes[usageScope][depth - 1].color; - } - - if (newScope == oldScope) - return; - - _scope[*node] = newScope; - - const std::vector& args = node->getArguments(); - size_t aSize = args.size(); - for (size_t a = 0; a < aSize; a++) { - updateVarScopeUsage(args[a].getOperation(), newScope, oldScope); - } -} - -template -inline void CodeHandler::addScopeToVarOrder(size_t scope, - size_t& e) { - std::vector& vorder = _scopedVariableOrder[scope]; - - const size_t vsize = vorder.size(); - for (size_t p = 0; p < vsize; p++) { - Node* node = vorder[p]; - CGOpCode op = node->getOperationType(); - - if (op == CGOpCode::LoopEnd || op == CGOpCode::EndIf || op == CGOpCode::ElseIf || op == CGOpCode::Else) { - CPPADCG_ASSERT_UNKNOWN(!node->getArguments().empty()); - - Node* beginScopeNode = node->getArguments()[0].getOperation(); - CPPADCG_ASSERT_UNKNOWN(beginScopeNode != nullptr); - - addScopeToVarOrder(_scope[*beginScopeNode], e); - } - - //std::cout << "e:" << e << " " << vorder[p] << " scope:" << scope << " p:" << p << " " << *vorder[p] << std::endl; - _variableOrder[e++] = vorder[p]; - } -} - -template -inline size_t CodeHandler::findFirstDifferentScope(size_t color1, - size_t color2) { - CPPADCG_ASSERT_UNKNOWN(color1 < _scopes.size()); - CPPADCG_ASSERT_UNKNOWN(color2 < _scopes.size()); - - ScopePath& scopePath1 = _scopes[color1]; - ScopePath& scopePath2 = _scopes[color2]; - - size_t s1 = scopePath1.size(); - size_t s2 = scopePath2.size(); - size_t depth; - for (depth = 0; depth < s1 && depth < s2; depth++) { - if (scopePath1[depth].color != scopePath2[depth].color) { - break; - } - } - - return depth; -} - -template -inline void CodeHandler::optimizeIfs() { - if (_scopedVariableOrder.size() < 3) - return; // there has to be at least 2 ifs - - for (size_t scope = 0; scope < _scopedVariableOrder.size(); scope++) { - std::vector& vorder = _scopedVariableOrder[scope]; - - for (long p = vorder.size() - 1; p > 0; p--) { - Node* endIf = vorder[p]; - if (endIf->getOperationType() != CGOpCode::EndIf) - continue; - - long p1 = p - 1; - while (p1 >= 0) { - if (vorder[p1]->getOperationType() == CGOpCode::TmpDcl) { - p1--; - } else { - break; - } - } - Node* endIf1 = vorder[p1]; - if (endIf1->getOperationType() != CGOpCode::EndIf) - continue; - - // 2 consecutive ifs - Node* startIf = endIf->getArguments()[0].getOperation(); - Node* startIf1 = endIf1->getArguments()[0].getOperation(); - if (startIf->getOperationType() != CGOpCode::StartIf || startIf1->getOperationType() != CGOpCode::StartIf) - continue; - - Node* cond = startIf->getArguments()[0].getOperation(); - Node* cond1 = startIf1->getArguments()[0].getOperation(); - - CPPADCG_ASSERT_UNKNOWN(cond->getOperationType() == CGOpCode::IndexCondExpr || cond1->getOperationType() == CGOpCode::IndexCondExpr); - if (cond->getInfo() == cond1->getInfo()) { - /** - * same condition -> combine the contents into a single if - */ - const std::vector& eArgs = endIf->getArguments(); - std::vector& eArgs1 = endIf1->getArguments(); - - ScopeIDType ifScope = _scope[*startIf]; - ScopeIDType ifScope1 = _scope[*startIf1]; - std::vector& vorderIf = _scopedVariableOrder[ifScope]; - std::vector& vorderIf1 = _scopedVariableOrder[ifScope1]; - - startNewOperationTreeVisit(); - - // break cycles caused by dependencies on the previous if - for (size_t a = 1; a < eArgs.size(); a++) { // exclude the initial startIf - CPPADCG_ASSERT_UNKNOWN(eArgs[a].getOperation() != nullptr && eArgs[a].getOperation()->getOperationType() == CGOpCode::CondResult); - breakCyclicDependency(eArgs[a].getOperation(), ifScope, endIf1); - replaceScope(eArgs[a].getOperation(), ifScope, ifScope1); // update scope - } - - vorderIf1.insert(vorderIf1.end(), vorderIf.begin() + 1, vorderIf.end()); // exclude the initial startIf - - vorderIf.clear(); - - // update startIf - for (size_t a = 1; a < eArgs.size(); a++) { // exclude the initial startIf - CPPADCG_ASSERT_UNKNOWN(eArgs[a].getOperation() != nullptr && eArgs[a].getOperation()->getOperationType() == CGOpCode::CondResult); - eArgs[a].getOperation()->getArguments()[0] = Arg(*startIf1); - } - - // update endIf - eArgs1.insert(eArgs1.end(), eArgs.begin() + 1, eArgs.end()); - - // replace endIf - endIf->setOperation(CGOpCode::Alias, {*endIf1}); - - // remove one of the ifs - vorder.erase(vorder.begin() + p); - - // move nodes in scope containing the ifs - for (long pp = p1; pp < p - 1; pp++) { - vorder[pp] = vorder[pp + 1]; - } - vorder[p - 1] = endIf1; - } - } - } -} - -template -inline void CodeHandler::replaceScope(Node* node, - ScopeIDType oldScope, - ScopeIDType newScope) { - if (node == nullptr || _scope[*node] != oldScope) - return; - - _scope[*node] = newScope; - - const std::vector& args = node->getArguments(); - for (size_t a = 0; a < args.size(); a++) { - replaceScope(args[a].getOperation(), oldScope, newScope); - } -} - -template -inline void CodeHandler::breakCyclicDependency(Node* node, - size_t scope, - Node* endIf) { - if (node == nullptr || isVisited(*node)) - return; - - markVisited(*node); - - CGOpCode op = node->getOperationType(); - std::vector& args = node->getArguments(); - - if (op == CGOpCode::Tmp && args.size() > 1) { - Node* arg = args[1].getOperation(); - if (arg == endIf) { - // a dependency on LoopIndexedTmp could be added but - // it is not required since variable order was already decided - args.erase(args.begin() + 1); - } - } - - if (!containedInScope(*node, scope)) { - return; - } - - for (size_t a = 0; a < args.size(); a++) { - Node* arg = args[a].getOperation(); - if (arg == endIf) { - if (op == CGOpCode::StartIf || op == CGOpCode::LoopStart) { - args.erase(args.begin() + a); - a--; - } - } else { - breakCyclicDependency(arg, scope, endIf); - } - } -} - -template -inline bool CodeHandler::containedInScope(const Node& node, - ScopeIDType scope) { - ScopeIDType nScope = _scope[node]; - if (nScope == scope) - return true; - - return _scopes[nScope].size() >= _scopes[scope].size() && - _scopes[nScope][_scopes[scope].size() - 1].color == scope; -} - -template -inline bool CodeHandler::containsArgument(const Node& node, - const Node& arg) { - const std::vector& args = node.getArguments(); - for (size_t a = 0; a < args.size(); a++) { - if (args[a].getOperation() == &arg) { - return true; - } - } - return false; -} - -template -void CodeHandler::registerAtomicFunction(CGAbstractAtomicFun& atomic) { - _atomicFunctions[atomic.getId()] = &atomic; -} - -template -void CodeHandler::checkVariableCreation(Node& code) { - const std::vector& args = code.getArguments(); - - size_t aSize = args.size(); - for (size_t argIndex = 0; argIndex < aSize; argIndex++) { - if (args[argIndex].getOperation() == nullptr) { - continue; - } - - Node& arg = *args[argIndex].getOperation(); - CGOpCode aType = arg.getOperationType(); - - if (!isVisited(arg)) { - // dependencies not visited yet - checkVariableCreation(arg); - - if (aType == CGOpCode::LoopEnd || aType == CGOpCode::ElseIf || aType == CGOpCode::Else || aType == CGOpCode::EndIf) { - if (_varId[arg] == 0) { - // ID value is not really used but must be non-zero - _varId[arg] = std::numeric_limits::max(); - } - } else if (aType == CGOpCode::AtomicForward || aType == CGOpCode::AtomicReverse) { - /** - * Save atomic function related information - */ - CPPADCG_ASSERT_UNKNOWN(arg.getArguments().size() > 1); - CPPADCG_ASSERT_UNKNOWN(arg.getInfo().size() > 1); - size_t id = arg.getInfo()[0]; - - size_t pos; - const std::string& atomicName = _atomicFunctions.at(id)->afun_name(); - std::map::const_iterator itName2Idx; - itName2Idx = _atomicFunctionName2Index.find(atomicName); - - if (itName2Idx == _atomicFunctionName2Index.end()) { - pos = _atomicFunctionsOrder->size(); - _atomicFunctionsOrder->push_back(atomicName); - _atomicFunctionName2Index[atomicName] = pos; - _atomicFunctionsMaxForward.push_back(-1); - _atomicFunctionsMaxReverse.push_back(-1); - } else { - pos = itName2Idx->second; - } - - if (aType == CGOpCode::AtomicForward) { - int p = arg.getInfo()[2]; - _atomicFunctionsMaxForward[pos] = std::max(_atomicFunctionsMaxForward[pos], p); - } else { - int p = arg.getInfo()[1]; - _atomicFunctionsMaxReverse[pos] = std::max(_atomicFunctionsMaxReverse[pos], p); - } - } - - /** - * make sure new temporary variables are NOT created for - * the independent variables and that a dependency did - * not use it first - */ - if (_varId[arg] == 0 || !isIndependent(arg)) { - if (aType == CGOpCode::LoopIndexedIndep) { - // ID value not really used but must be non-zero - _varId[arg] = std::numeric_limits::max(); - } else if (aType == CGOpCode::Alias) { - continue; // should never be added to the evaluation queue - } else if (aType == CGOpCode::Tmp) { - _varId[arg] = std::numeric_limits::max(); - } else if (aType == CGOpCode::LoopStart || - aType == CGOpCode::LoopEnd || - aType == CGOpCode::StartIf || - aType == CGOpCode::ElseIf || - aType == CGOpCode::Else || - aType == CGOpCode::EndIf) { - /** - * Operation that mark a change in variable scope - * are always added - */ - addToEvaluationQueue(arg); - if (_varId[arg] == 0) { - // ID value is not really used but must be non-zero - _varId[arg] = std::numeric_limits::max(); - } - } else if (aType == CGOpCode::Pri) { - addToEvaluationQueue(arg); - if (_varId[arg] == 0) { - // ID value is not really used but must be non-zero - _varId[arg] = std::numeric_limits::max(); - } - } else if (aType == CGOpCode::TmpDcl) { - addToEvaluationQueue(arg); - - _varId[arg] = _idCount; - _idCount++; - - } else if (_lang->createsNewVariable(arg, getTotalUsageCount(arg)) || - _lang->requiresVariableArgument(code.getOperationType(), argIndex)) { - - addToEvaluationQueue(arg); - - if (_varId[arg] == 0) { - if (aType == CGOpCode::AtomicForward || aType == CGOpCode::AtomicReverse) { - _varId[arg] = _idAtomicCount; - _idAtomicCount++; - } else if (aType == CGOpCode::LoopIndexedDep || aType == CGOpCode::LoopIndexedTmp) { - // ID value not really used but must be non-zero - _varId[arg] = std::numeric_limits::max(); - } else if (aType == CGOpCode::ArrayCreation) { - // a temporary array - size_t arraySize = arg.getArguments().size(); - _varId[arg] = _idArrayCount; - _idArrayCount += arraySize; - } else if (aType == CGOpCode::SparseArrayCreation) { - // a temporary array - size_t nnz = arg.getArguments().size(); - _varId[arg] = _idSparseArrayCount; - _idSparseArrayCount += nnz; - } else { - // a single temporary variable - _varId[arg] = _idCount; - _idCount++; - } - } - } - - } - } - - markVisited(arg); - - } - -} - -template -inline void CodeHandler::addToEvaluationQueue(Node& arg) { - ScopeIDType scope = _scope[arg]; - if (scope >= _scopedVariableOrder.size()) { - _scopedVariableOrder.resize(scope + 1); - } - - if (_scopedVariableOrder[scope].empty() && - scope != 0 && // the upper most scope does not need any special node at the beginning - _scopes[scope].back().end->getArguments()[0].getOperation() != &arg) { - // the first node must be a beginning of a scope - checkVariableCreation(*_scopes[scope].back().end); // go inside a scope from the end - } - - // must be after checkVariableCreation() because _scopedVariableOrder might be resized - std::vector& varOrder = _scopedVariableOrder[scope]; - - if (varOrder.size() == varOrder.capacity()) { - varOrder.reserve((varOrder.size() * 3) / 2 + 1); - } - - varOrder.push_back(&arg); -} - -template -inline void CodeHandler::reduceTemporaryVariables(ArrayWrapper& dependent) { - - reorderOperations(dependent); - - /** - * determine the last line where each temporary variable is used - */ - startNewOperationTreeVisit(); - - for (size_t i = 0; i < dependent.size(); i++) { - Node* node = dependent[i].getOperationNode(); - if (node != nullptr) { - if (!isVisited(*node)) { - // dependencies not visited yet - determineLastTempVarUsage(*node); - } - markVisited(*node); - } - } - - // where temporary variables can be released - std::vector> tempVarRelease(_variableOrder.size()); - for (size_t i = 0; i < _variableOrder.size(); i++) { - Node* var = _variableOrder[i]; - if (isTemporary(*var) || isTemporaryArray(*var) || isTemporarySparseArray(*var)) { - size_t releaseLocation = getLastUsageEvaluationOrder(*var) - 1; - tempVarRelease[releaseLocation].push_back(var); - } - } - - - /** - * Redefine temporary variable IDs - */ - std::vector freedVariables; // variable IDs no longer in use - _idCount = _minTemporaryVarID; - ArrayIdCompresser arrayComp(_varId, _idArrayCount); - ArrayIdCompresser sparseArrayComp(_varId, _idSparseArrayCount); - - for (size_t i = 0; i < _variableOrder.size(); i++) { - Node& var = *_variableOrder[i]; - - const std::vector& released = tempVarRelease[i]; - for (size_t r = 0; r < released.size(); r++) { - if (isTemporary(*released[r])) { - freedVariables.push_back(_varId[*released[r]]); - } else if (isTemporaryArray(*released[r])) { - arrayComp.addFreeArraySpace(*released[r]); - } else if (isTemporarySparseArray(*released[r])) { - sparseArrayComp.addFreeArraySpace(*released[r]); - } - } - - if (isTemporary(var)) { - // a single temporary variable - if (freedVariables.empty()) { - _varId[var] = _idCount; - _idCount++; - } else { - size_t id = freedVariables.back(); - freedVariables.pop_back(); - _varId[var] = id; - } - } else if (isTemporaryArray(var)) { - // a temporary array - size_t arrayStart = arrayComp.reserveArraySpace(var); - _varId[var] = arrayStart + 1; - } else if (isTemporarySparseArray(var)) { - // a temporary array - size_t arrayStart = sparseArrayComp.reserveArraySpace(var); - _varId[var] = arrayStart + 1; - } - - } - - _idArrayCount = arrayComp.getIdCount(); - _idSparseArrayCount = sparseArrayComp.getIdCount(); -} - -template -inline void CodeHandler::reorderOperations(ArrayWrapper& dependent) { - // determine the location of the last temporary variable used for each dependent - startNewOperationTreeVisit(); - - // normal dependent nodes - for (size_t i = 0; i < dependent.size(); ++i) { - Node* node = dependent[i].getOperationNode(); - if (node != nullptr) { - reorderOperation(*node); - } - } - - // dependent nodes defined inside loops - for (const LoopEndOperationNode* endNode : _loops.endNodes) { - const std::vector& args = endNode->getArguments(); - for (size_t i = 1; i < args.size(); ++i) { - CPPADCG_ASSERT_UNKNOWN(args[i].getOperation() != nullptr); - // TODO: also consider CGOpCode::LoopIndexedDep inside a CGOpCode::endIf - if (args[i].getOperation()->getOperationType() == CGOpCode::LoopIndexedDep) { - reorderOperation(*args[i].getOperation()); - } - } - } -} - -template -inline void CodeHandler::reorderOperation(Node& node) { - /** - * determine the location of the last temporary variable - */ - size_t depPos = getEvaluationOrder(node); - size_t lastTmpPos = depPos; - if (!isVisited(node)) { - // dependencies not visited yet - lastTmpPos = findLastTemporaryLocation(node); - } - markVisited(node); - - /** - * move dependent if beneficial - */ - if (lastTmpPos == depPos || lastTmpPos + 1 == depPos) { - return; // should not change location of the evaluation of this dependent - } - - // should only move if there are temporaries which could use other temporaries released by the dependent - bool foundTemporaries = false; - size_t newPos; - for (size_t l = lastTmpPos + 1; l < depPos; ++l) { - const auto* n = _variableOrder[l - 1]; - if (isTemporary(*n) || isTemporaryArray(*n) || isTemporarySparseArray(*n)) { - foundTemporaries = true; - newPos = l; - break; - } else { - /** - * Must be in same scope - */ - CGOpCode op = n->getOperationType(); - if (op == CGOpCode::StartIf) { - // must not change scope (find the end of this conditional statement) - ++l; - while (l < depPos) { - const auto* node2 = _variableOrder[l - 1]; - if (node2->getOperationType() == CGOpCode::EndIf && - node2->getArguments()[0].getOperation() == n) { - break; // found the end (returned to the same scope) - } - ++l; - } - - } else if (op == CGOpCode::LoopStart) { - // must not change scope (find the end of this loop statement) - ++l; - while (l < depPos) { - const auto* node2 = _variableOrder[l - 1]; - if (node2->getOperationType() == CGOpCode::LoopEnd && - &static_cast*> (node2)->getLoopStart() == n) { - break; // found the end (returned to the same scope) - } - ++l; - } - } - } - } - - if (foundTemporaries) { - // move variables - repositionEvaluationQueue(depPos, newPos); - } -} - -template -inline size_t CodeHandler::findLastTemporaryLocation(Node& node) { - size_t depOrder = getEvaluationOrder(node); - size_t maxTmpOrder = 0; // lowest possible value is 1 - for (const Arg& it : node) { - if (it.getOperation() != nullptr) { - Node& arg = *it.getOperation(); - CGOpCode aOp = arg.getOperationType(); - if (aOp == CGOpCode::LoopEnd || aOp == CGOpCode::EndIf || aOp == CGOpCode::ElseIf || aOp == CGOpCode::Else) { - continue; //should not move variables to a different scope - } - - if (aOp == CGOpCode::Index) { - size_t iorder = getEvaluationOrder(static_cast&> (arg).getIndexCreationNode()); - if (iorder > maxTmpOrder) - maxTmpOrder = iorder; - } else if (getEvaluationOrder(arg) == depOrder) { - // dependencies not visited yet - size_t orderNew = findLastTemporaryLocation(arg); - if (orderNew > maxTmpOrder) - maxTmpOrder = orderNew; - } else { - // no need to visit dependencies - if (getEvaluationOrder(arg) > maxTmpOrder) - maxTmpOrder = getEvaluationOrder(arg); - } - } - } - - return maxTmpOrder == 0 ? depOrder : maxTmpOrder; -} - -template -inline void CodeHandler::repositionEvaluationQueue(size_t fromPos, size_t toPos) { - // Warning: there is an offset of 1 between the evaluation order saved - // in the node and the actual location in the _variableOrder - CPPADCG_ASSERT_UNKNOWN(fromPos > toPos); - Node* node = _variableOrder[fromPos - 1]; // node to be moved - - // move variables in between the order change - for (size_t l = fromPos - 1; l > toPos - 1; --l) { - _variableOrder[l] = _variableOrder[l - 1]; - updateEvaluationQueueOrder(*_variableOrder[l], l + 1); - } - - _variableOrder[toPos - 1] = node; - updateEvaluationQueueOrder(*node, toPos); -} - -template -inline void CodeHandler::determineLastTempVarUsage(Node& node) { - CGOpCode op = node.getOperationType(); - - if (op == CGOpCode::LoopEnd) { - LoopEndOperationNode& loopEnd = static_cast&> (node); - _loops.depth++; - _loops.outerVars.resize(_loops.depth + 1); - _loops.startEvalOrder.push_back(getEvaluationOrder(loopEnd.getLoopStart())); - - } else if (op == CGOpCode::LoopStart) { - _loops.depth--; // leaving the current loop - } - - /** - * count variable usage - */ - for (const Arg& it : node.getArguments()) { - if (it.getOperation() != nullptr) { - Node& arg = *it.getOperation(); - - if (!isVisited(arg)) { - // dependencies not visited yet - determineLastTempVarUsage(arg); - } - - markVisited(arg); - - size_t order = getEvaluationOrder(node); - Node* aa = getOperationFromAlias(arg); // follow alias! - if (aa != nullptr) { - if (getLastUsageEvaluationOrder(*aa) < order) { - setLastUsageEvaluationOrder(*aa, order); - } - - if (_loops.depth >= 0 && - getEvaluationOrder(*aa) < _loops.startEvalOrder[_loops.depth] && - isTemporary(*aa)) { - // outer variable used inside the loop - _loops.outerVars[_loops.depth].insert(aa); - } - } - } - } - - if (op == CGOpCode::LoopEnd) { - /** - * temporary variables from outside the loop which are used - * within the loop cannot be overwritten inside that loop - */ - size_t order = getEvaluationOrder(node); - - const std::set& outerLoopUsages = _loops.outerVars.back(); - for (Node* outerVar : outerLoopUsages) { - Node* aa = getOperationFromAlias(*outerVar); // follow alias! - if (aa != nullptr && getLastUsageEvaluationOrder(*aa) < order) - setLastUsageEvaluationOrder(*aa, order); - } - - _loops.depth--; - _loops.outerVars.pop_back(); - _loops.startEvalOrder.pop_back(); - - } else if (op == CGOpCode::LoopStart) { - _loops.depth++; // coming back to the loop - } - -} - -template -inline void CodeHandler::dependentAdded2EvaluationQueue(Node& node) { - for (const Arg& a : node.getArguments()) { - if (a.getOperation() != nullptr) { - Node& arg = *a.getOperation(); - if (getEvaluationOrder(arg) == 0) { - setEvaluationOrder(arg, getEvaluationOrder(node)); - dependentAdded2EvaluationQueue(arg); - } - } - } -} - -template -inline void CodeHandler::updateEvaluationQueueOrder(Node& node, - size_t newEvalOrder) { - size_t oldEvalOrder = getEvaluationOrder(node); - - setEvaluationOrder(node, newEvalOrder); - - for (const Arg& a : node.getArguments()) { - if (a.getOperation() != nullptr) { - Node& arg = *a.getOperation(); - if (getEvaluationOrder(arg) == oldEvalOrder) - updateEvaluationQueueOrder(arg, newEvalOrder); - } - } -} - -template -inline void CodeHandler::findVariableDependencies() { - _variableDependencies.resize(_variableOrder.size()); - - for (size_t i = 0; i < _variableOrder.size(); i++) { - Node& var = *_variableOrder[i]; - - _variableDependencies[i].clear(); - startNewOperationTreeVisit(); - - for (const auto& a : var) { - if (a.getOperation() != nullptr) { - findVariableDependencies(i, *a.getOperation()); - } - } - } -} - -template -inline void CodeHandler::findVariableDependencies(size_t i, - Node& node) { - if (!isVisited(node)) { - markVisited(node); - - if(_varId[node] != 0) { - _variableDependencies[i].insert(&node); - } else { - for (const auto& a : node) { - if (a.getOperation() != nullptr) { - findVariableDependencies(i, *a.getOperation()); - } - } - } - } -} - -template -inline bool CodeHandler::isIndependent(const Node& arg) const { - return arg.getOperationType() == CGOpCode::Inv; -} - -template -inline bool CodeHandler::isTemporary(const Node& arg) const { - CGOpCode op = arg.getOperationType(); - return op != CGOpCode::ArrayCreation && // classified as TemporaryArray - op != CGOpCode::SparseArrayCreation && // classified as TemporarySparseArray - op != CGOpCode::AtomicForward && - op != CGOpCode::AtomicReverse && - op != CGOpCode::LoopStart && - op != CGOpCode::LoopEnd && - op != CGOpCode::StartIf && - op != CGOpCode::ElseIf && - op != CGOpCode::Else && - op != CGOpCode::EndIf && - op != CGOpCode::LoopIndexedDep && - op != CGOpCode::LoopIndexedIndep && - op != CGOpCode::LoopIndexedTmp && // not considered as a temporary (the temporary is CGTmpDclOp) - op != CGOpCode::Index && - op != CGOpCode::IndexAssign && - op != CGOpCode::Tmp && // not considered as a temporary (the temporary is CGTmpDclOp) - _varId[arg] >= _minTemporaryVarID; -} - -template -inline bool CodeHandler::isTemporaryArray(const Node& arg) { - return arg.getOperationType() == CGOpCode::ArrayCreation; -} - -template -inline bool CodeHandler::isTemporarySparseArray(const Node& arg) { - return arg.getOperationType() == CGOpCode::SparseArrayCreation; -} - -template -inline OperationNode* CodeHandler::getOperationFromAlias(Node& alias) { - if (alias.getOperationType() != CGOpCode::Alias) { - return &alias; - } else { - Node* aa = &alias; - do { - CPPADCG_ASSERT_UNKNOWN(aa->getArguments().size() == 1); - aa = aa->getArguments()[0].getOperation(); - } while (aa != nullptr && aa->getOperationType() == CGOpCode::Alias); - return aa; - } -} - -template -inline size_t CodeHandler::getEvaluationOrder(const Node& node) const { - return _evaluationOrder[node]; -} - -template -inline void CodeHandler::setEvaluationOrder(Node& node, - size_t order) { - CPPADCG_ASSERT_UNKNOWN(order <= _variableOrder.size()); - _evaluationOrder[node] = order; -} - -template -inline size_t CodeHandler::getLastUsageEvaluationOrder(const Node& node) const { - return _lastUsageOrder[node]; -} - -template -inline void CodeHandler::setLastUsageEvaluationOrder(const Node& node, - size_t last) { - CPPADCG_ASSERT_UNKNOWN(last <= _variableOrder.size()); // _lastUsageOrder[node] = 0 means that it was never used - _lastUsageOrder[node] = last; - - CGOpCode op = node.getOperationType(); - if (op == CGOpCode::ArrayElement) { - Node* array = node.getArguments()[0].getOperation(); - CPPADCG_ASSERT_UNKNOWN(array->getOperationType() == CGOpCode::ArrayCreation); - if (getLastUsageEvaluationOrder(*array) < last) { - setLastUsageEvaluationOrder(*array, last); - } - } else if (op == CGOpCode::Tmp) { - Node* declr = node.getArguments()[0].getOperation(); - CPPADCG_ASSERT_UNKNOWN(declr->getOperationType() == CGOpCode::TmpDcl); - if (getLastUsageEvaluationOrder(*declr) < last) { - setLastUsageEvaluationOrder(*declr, last); - } - } -} - -template -inline size_t CodeHandler::getTotalUsageCount(const Node& node) const { - return _totalUseCount[node]; -} - -template -inline void CodeHandler::setTotalUsageCount(const Node& node, - size_t cout) { - _totalUseCount[node] = cout; -} - -template -inline void CodeHandler::increaseTotalUsageCount(const Node& node) { - _totalUseCount[node]++; -} - -template -inline void CodeHandler::resetManagedNodes() { - _variableOrder.clear(); - _scopedVariableOrder.resize(1); - _scopedVariableOrder[0].clear(); - _evaluationOrder.fill(0); - _lastUsageOrder.fill(0); - _totalUseCount.fill(0); - _varId.fill(0); - _scope.fill(0); -} - -} // END cg namespace -} // END CppAD namespace - -#endif diff --git a/ct_core/include/ct/external/cppad/cg/code_handler_loops.hpp b/ct_core/include/ct/external/cppad/cg/code_handler_loops.hpp deleted file mode 100644 index eb1e338a9..000000000 --- a/ct_core/include/ct/external/cppad/cg/code_handler_loops.hpp +++ /dev/null @@ -1,143 +0,0 @@ -#ifndef CPPAD_CG_CODE_HANDLER_LOOPS_INCLUDED -#define CPPAD_CG_CODE_HANDLER_LOOPS_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -const std::map*>& CodeHandler::getLoops() const { - return _loops.loopModels; -} - -template -inline LoopModel* CodeHandler::getLoop(size_t loopId) const { - return _loops.getLoop(loopId); -} - -template -inline size_t CodeHandler::addLoopDependentIndexPattern(IndexPattern& jacPattern) { - return _loops.addDependentIndexPattern(jacPattern); -} - -template -inline void CodeHandler::manageLoopDependentIndexPattern(const IndexPattern* pattern) { - _loops.manageDependentIndexPattern(pattern); -} - -template -inline size_t CodeHandler::addLoopIndependentIndexPattern(IndexPattern& pattern, - size_t hint) { - return _loops.addIndependentIndexPattern(pattern, hint); -} - -template -inline void CodeHandler::LoopData::prepare4NewSourceGen() { - indexes.clear(); - indexRandomPatterns.clear(); - outerVars.clear(); - depth = -1; - startEvalOrder.clear(); - endNodes.clear(); - - endNodes.reserve(loopModels.size()); -} - -template -inline void CodeHandler::LoopData::reset() { - loopModels.clear(); - indexes.clear(); - indexRandomPatterns.clear(); - dependentIndexPatterns.clear(); - independentIndexPatterns.clear(); - endNodes.clear(); - - for (const IndexPattern* itip : dependentIndexPatternManaged) { - delete itip; - } - dependentIndexPatternManaged.clear(); -} - -template -inline const std::string* CodeHandler::LoopData::getLoopName(size_t id) const { - typename std::map*>::const_iterator it; - it = loopModels.find(id); - if (it != loopModels.end()) - return &(it->second->afun_name()); - else - return nullptr; -} - -template -void CodeHandler::LoopData::registerModel(LoopModel& loop) { - loopModels[loop.getLoopId()] = &loop; -} - -template -LoopModel* CodeHandler::LoopData::getLoop(size_t loopId) const { - typename std::map*>::const_iterator it = loopModels.find(loopId); - if (it != loopModels.end()) { - return it->second; - } - - return nullptr; -} - -template -size_t CodeHandler::LoopData::addDependentIndexPattern(IndexPattern& pattern) { - size_t size = dependentIndexPatterns.size(); - if (dependentIndexPatterns.capacity() == size) { - dependentIndexPatterns.reserve((size * 3) / 2 + 1); - } - dependentIndexPatterns.push_back(&pattern); - - return size; -} - -template -void CodeHandler::LoopData::manageDependentIndexPattern(const IndexPattern* pattern) { - size_t sizeM = dependentIndexPatternManaged.size(); - if (dependentIndexPatternManaged.capacity() == sizeM) { - dependentIndexPatternManaged.reserve((sizeM * 3) / 2 + 1); - } - dependentIndexPatternManaged.push_back(pattern); -} - -template -size_t CodeHandler::LoopData::addIndependentIndexPattern(IndexPattern& pattern, size_t hint) { - size_t size = independentIndexPatterns.size(); - if (hint < size && independentIndexPatterns[hint] == &pattern) { - return hint; - } - if (independentIndexPatterns.capacity() == size) { - independentIndexPatterns.reserve((size * 3) / 2 + 1); - } - independentIndexPatterns.push_back(&pattern); - - return size; -} - -template -void CodeHandler::LoopData::addLoopEndNode(OperationNode& node) { - CPPADCG_ASSERT_UNKNOWN(node.getOperationType() == CGOpCode::LoopEnd); - LoopEndOperationNode& loopEnd = static_cast&> (node); - endNodes.push_back(&loopEnd); -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/code_handler_vector.hpp b/ct_core/include/ct/external/cppad/cg/code_handler_vector.hpp deleted file mode 100644 index bcdf945f0..000000000 --- a/ct_core/include/ct/external/cppad/cg/code_handler_vector.hpp +++ /dev/null @@ -1,240 +0,0 @@ -#ifndef CPPAD_CG_CODE_HANDLER_VECTOR_INCLUDED -#define CPPAD_CG_CODE_HANDLER_VECTOR_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -// forward declaration -template -class CodeHandler; - -/** - * A class for synchronization of data vectors associated with operation nodes - * managed by a code handler. - */ -template -class CodeHandlerVectorSync { - friend class CodeHandler; -protected: - CodeHandler* handler_; -public: - - inline CodeHandlerVectorSync(CodeHandler& handler) : - handler_(&handler) { - handler_->addVector(this); - } - - inline CodeHandlerVectorSync(const CodeHandlerVectorSync& orig) : - handler_(orig.handler_) { - handler_->addVector(this); - } - - virtual ~CodeHandlerVectorSync() { - if (handler_ != nullptr) - handler_->removeVector(this); - } - - inline CodeHandler& getHandler() const { - return *handler_; - } - -protected: - /** - * @param start The index of the first OperationNode that was deleted - * @param end The index after the last OperationNode that was deleted - */ - virtual void nodesErased(size_t start, - size_t end) = 0; -}; - -/** - * A vector for data associated with operation nodes managed by a code handler. - * - * @author Joao Leal - */ -template -class CodeHandlerVector : public CodeHandlerVectorSync { -public: - typedef typename std::vector::iterator iterator; - typedef typename std::vector::const_iterator const_iterator; - typedef typename std::vector::const_reverse_iterator const_reverse_iterator; - typedef typename std::vector::reverse_iterator reverse_iterator; - typedef typename std::vector::reference reference; - typedef typename std::vector::const_reference const_reference; -private: - /** - * data vector - */ - std::vector data_; -public: - - inline CodeHandlerVector(CodeHandler& handler) : - CodeHandlerVectorSync(handler) { - } - - inline CodeHandlerVector(const CodeHandlerVector& orig) : - CodeHandlerVectorSync(orig), - data_(orig.data_) { - } - - inline void clear() { - data_.clear(); - } - - inline void adjustSize() { - size_t s = this->handler_->getManagedNodesCount(); - if (s >= data_.capacity()) { - data_.reserve(s * 3 / 2 + 1); - } - data_.resize(s); - } - - inline void adjustSize(const OperationNode& node) { - CPPADCG_ASSERT_UNKNOWN(node.getCodeHandler() == this->handler_); - - size_t p = node.getHandlerPosition(); - if (p == std::numeric_limits::max()) - throw CGException("An operation node is not managed by this code handler"); - - if (p >= data_.size()) - adjustSize(); - } - - inline reference get(const OperationNode& node) { - CPPADCG_ASSERT_UNKNOWN(node.getCodeHandler() == this->handler_); - - size_t p = node.getHandlerPosition(); - if (p == std::numeric_limits::max()) - throw CGException("An operation node is not managed by this code handler"); - CPPADCG_ASSERT_UNKNOWN(p < data_.size()); - - return data_[p]; - } - - inline const_reference get(const OperationNode& node) const { - CPPADCG_ASSERT_UNKNOWN(node.getCodeHandler() == this->handler_); - - size_t p = node.getHandlerPosition(); - if (p == std::numeric_limits::max()) - throw CGException("An operation node is not managed by this code handler"); - CPPADCG_ASSERT_UNKNOWN(p < data_.size()); - - return data_[p]; - } - - inline void set(const OperationNode& node, - const T& val) { - CPPADCG_ASSERT_UNKNOWN(node.getCodeHandler() == this->handler_); - - size_t p = node.getHandlerPosition(); - if (p == std::numeric_limits::max()) - throw CGException("An operation node is not managed by this code handler"); - CPPADCG_ASSERT_UNKNOWN(p < data_.size()); - - data_[node.getHandlerPosition()] = val; - } - - inline size_t size() const { - return data_.size(); - } - - inline bool empty() const { - return data_.empty(); - } - - inline void fill(const T& v) { - std::fill(data_.begin(), data_.end(), v); - } - - // iterators - - inline iterator begin() { - return data_.begin(); - } - - inline const_iterator begin() const { - return data_.begin(); - } - - inline iterator end() { - return data_.end(); - } - - inline const_iterator end() const { - return data_.end(); - } - - inline reverse_iterator rbegin() { - return data_.rbegin(); - } - - inline const_reverse_iterator rbegin() const { - return data_.rbegin(); - } - - inline reverse_iterator rend() { - return data_.rend(); - } - - inline const_reverse_iterator rend() const { - return data_.rend(); - } - - inline const_iterator cbegin() const noexcept { - return data_.cbegin(); - } - - inline const_iterator cend() const noexcept { - return data_.cend(); - } - - inline const_reverse_iterator crbegin() const noexcept { - return data_.crbegin(); - } - - inline const_reverse_iterator crend() const noexcept { - return data_.crend(); - } -protected: - - virtual void nodesErased(size_t start, - size_t end) override { - if (start < data_.size()) { - end = std::min(end, data_.size()); - data_.erase(data_.begin() + start, data_.begin() + end); - } - } - -public: - - /** - * operators - */ - inline reference operator[](const OperationNode& node) { - return get(node); - } - - inline const_reference operator[](const OperationNode& node) const { - return get(node); - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif diff --git a/ct_core/include/ct/external/cppad/cg/collect_variable.hpp b/ct_core/include/ct/external/cppad/cg/collect_variable.hpp deleted file mode 100644 index 9234fb7c6..000000000 --- a/ct_core/include/ct/external/cppad/cg/collect_variable.hpp +++ /dev/null @@ -1,288 +0,0 @@ -#ifndef CPPAD_CG_COLLECT_VARIABLE_INCLUDED -#define CPPAD_CG_COLLECT_VARIABLE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include -#include - -namespace CppAD { -namespace cg { - -template -inline CG CodeHandler::collectVariable(OperationNode& expression, - const SourceCodePath& path1, - const SourceCodePath& path2, - size_t lastCommon) { - CPPADCG_ASSERT_UNKNOWN(lastCommon >= 0); - CPPADCG_ASSERT_UNKNOWN(path1.size() > lastCommon); - CPPADCG_ASSERT_UNKNOWN(path2.size() > lastCommon); - -#ifndef NDEBUG - /** - * Check common path - */ - for(size_t i = 0;i < lastCommon; ++i) { - // compare with the first path - CPPADCG_ASSERT_UNKNOWN(path2[i] == path1[i]); - } -#endif - - //std::cout << "common sub-expression (before):\n"; - //printExpression(*path1[lastCommon].node); - - SourceCodePath leftPath(path1.begin() + lastCommon, path1.end()); - SourceCodePath rightPath(path2.begin() + lastCommon, path2.end()); - - CG subExpression = collectVariableAddSub(leftPath, rightPath); - - //std::cout << "common sub-expression (after):\n"; - //printExpression(subExpression); - - /** - * Replace the new expression - */ - std::vector*> replace(lastCommon + 1, nullptr); - //replace.back() = &subExpression; - std::vector*>*> replaceOnPath{&replace}; - - SourceCodePath initPath(path1.begin(), path1.begin() + lastCommon + 1); - std::vector initPaths{&initPath}; - - //std::map*, CG > replacementNodes; - //replacementNodes[path1[lastCommon].node] = subExpression; // it might be used in more places within the model - - // use same independent variables - std::vector> indep(this->_independentVariables.size()); - for (size_t i = 0; i < indep.size(); ++i) - indep[i] = CG(*this->_independentVariables[i]); - - CG expressionOrig(expression); - CG expression2; - - size_t bifurcations = 0; - BidirGraph graphToCommon = findPathGraph(expression, *path1[lastCommon].node, bifurcations); - std::map*, CG> replacementNodes; - replacementNodes[&graphToCommon[*path1[lastCommon].node]] = subExpression; - - EvaluatorCloneSolve e(*this, graphToCommon, replacementNodes); - e.evaluate(indep.data(), indep.size(), - &expression2, &expressionOrig, 1); - - - //std::cout << "expression before replacement:\n"; - //printExpression(expressionOrig); - //printDotExpression(expressionOrig); - - //std::cout << "expression after replacement:\n"; - //printExpression(expression2); - // TODO: - // exp(x)*exp(x+1) = exp(x+x+1) - // pow(2, x)*pow(2, x+1) = pow(2, x+x+1) - // 1 / (2*x) + 2 / (3*x) = (1*3 + 2*2) / (6*x) - - return expression2; -} - -template -inline CG CodeHandler::collectVariableAddSub(const SourceCodePath& pathLeft, - const SourceCodePath& pathRight) { - /** - * Argument validation - */ - if(pathLeft[0].node == nullptr) { - throw CGException("Invalid path!"); - } else if(pathLeft[0].node != pathRight[0].node) { - throw CGException("The first element in each path must be the same."); - } - - auto& expression = *pathLeft[0].node; - - auto initCommonOp = expression.getOperationType(); - if (initCommonOp != CGOpCode::Add && - initCommonOp != CGOpCode::Sub) { - throw CGException("Invalid path! It must start with either an addition or subtraction."); - } - - if(pathLeft.back().node == nullptr || pathRight.back().node == nullptr) - throw CGException("Invalid path! It must end with a non null node."); - - if(pathLeft.back().node != pathRight.back().node) - throw CGException("Invalid paths! They must end with the same node."); - - OperationNode& var = *pathLeft.back().node; - - /** - * Check operations after the divergence - */ - isCollectableVariableAddSub(pathLeft, pathRight, true); - - /** - * - */ - CG zero(0); - std::array*>, 2> replace; // replacements for the existing operations - - std::vector paths{&pathLeft, &pathRight}; - - CG cSum; - - for (size_t j = 0; j < paths.size(); ++j) { - const auto& p = *paths[j]; - replace[j] = std::vector*>(p.size(), nullptr); - replace[j].back() = &zero; // the last node is always removed (its the variable we want to extract) - - /** - * find the coefficient which will multiply the variable - */ - CG c = 1; - if (initCommonOp == CGOpCode::Sub && j == 1) { - c = -1; - } - - for (size_t i = 1; i < p.size() - 1; ++i) { // the last node is what we want to extract - const auto* node = p[i].node; - if (node == nullptr) { - throw CGException("Failed to combine multiple occurrences of a variable into one expression"); - } - - auto op = node->getOperationType(); - - if (op == CGOpCode::Add) { - continue; - - } else if (op == CGOpCode::Sub) { - if (p[i - 1].argIndex == 1) - c = -c; - else - continue; - - } else if (op == CGOpCode::UnMinus) { - c = -c; - - } else if (op == CGOpCode::Mul) { - CPPADCG_ASSERT_UNKNOWN(p[i].argIndex == 0 || p[i].argIndex == 1); - const auto& pArgs = node->getArguments(); - c *= (p[i].argIndex == 0) ? pArgs[1] : pArgs[0]; - - } else if (op == CGOpCode::Div) { - CPPADCG_ASSERT_UNKNOWN(p[i].argIndex == 0); - c /= CG(node->getArguments()[1]); - - } else if (op == CGOpCode::Alias) { - continue; - - } else { - // should never get here - CPPADCG_ASSERT_UNKNOWN(false); - } - - } - - // - cSum += c; - - for (size_t i1 = p.size() - 1; i1 > 0; --i1) { - size_t i = i1 - 1; - if (p[i].node->getOperationType() == CGOpCode::Mul || - p[i].node->getOperationType() == CGOpCode::UnMinus || - p[i].node->getOperationType() == CGOpCode::Div || - p[i].node->getOperationType() == CGOpCode::Alias) { - replace[j][i] = &zero; - } else { - break; - } - } - } - - const auto& replaceLeft = replace[0]; - const auto& replaceRight = replace[1]; - bool keepCommon = replaceLeft[1] == nullptr || replaceRight[1] == nullptr; - - /** - * Clone operations in expression without var - */ - CG expression2; - if (keepCommon) { - std::vector*>*> replaceOnPath{&replaceLeft, &replaceRight}; - EvaluatorCloneSolve e(*this, paths, replaceOnPath); - - std::vector> indep(this->_independentVariables.size()); - for (size_t i = 0; i < indep.size(); ++i) - indep[i] = CG(*this->_independentVariables[i]); - - CG expressionOrig(expression); - - e.evaluate(indep.data(), indep.size(), - &expression2, &expressionOrig, 1); - } - - /** - * add term for variable - */ - CG v(var); - return cSum * v + expression2; -} - -template -inline bool CodeHandler::isCollectableVariableAddSub(const SourceCodePath& pathLeft, - const SourceCodePath& pathRight, - bool throwEx) { - /** - * Check operations after the divergence - */ - std::vector paths{&pathLeft, &pathRight}; - for (const SourceCodePath* p: paths) { - for (size_t i = 1; i < p->size() - 1; ++i) { // the last node does not have to be +, -, or * - const auto* node = (*p)[i].node; - - if (node == nullptr) { - if (throwEx) - throw CGException("Failed to combine multiple occurrences of a variable into one expression"); - return false; - } - - auto op = node->getOperationType(); - if (op != CGOpCode::Add && - op != CGOpCode::Sub && - op != CGOpCode::Mul && - op != CGOpCode::UnMinus && - op != CGOpCode::Alias) { - - if (op == CGOpCode::Div) { - if ((*p)[i].argIndex != 0) { - if (throwEx) - throw CGException("Unable to combine operations which are present in denominators (not implemented yet)."); - return false; - } else { - continue; - } - } - - if (throwEx) - throw CGException("Failed to combine multiple occurrences of a variable into one expression." - " Unable to combine operations diverging at a '", op, "' operation."); - return false; - } - } - } - - return true; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/compare.hpp b/ct_core/include/ct/external/cppad/cg/compare.hpp deleted file mode 100644 index fb052e155..000000000 --- a/ct_core/include/ct/external/cppad/cg/compare.hpp +++ /dev/null @@ -1,71 +0,0 @@ -#ifndef CPPAD_CG_COMPARE_INCLUDED -#define CPPAD_CG_COMPARE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -inline bool operator ==(const CG &left, const CG &right) { - if (left.isParameter() && right.isParameter()) { - return left.getValue() == right.getValue(); - } else if (left.isParameter() || right.isParameter()) { - return false; - } else { - return left.getOperationNode() == right.getOperationNode(); - } -} - -template -inline bool operator !=(const CG &left, const CG &right) { - if (left.isParameter() && right.isParameter()) { - return left.getValue() != right.getValue(); - } else if (left.isParameter() || right.isParameter()) { - return true; - } else { - return left.getOperationNode() != right.getOperationNode(); - } -} - -#define CPPAD_CG_OPERATOR(Op) \ - template \ - inline bool operator Op(const CG &left, const CG &right) { \ - if (left.isParameter() && right.isParameter()) { \ - return left.getValue() Op right.getValue(); \ - } else { \ - throw CGException("Cannot use the "#Op" comparison operator in non parameter variables");\ - } \ - } - -CPPAD_CG_OPERATOR(>) -CPPAD_CG_OPERATOR( >=) -CPPAD_CG_OPERATOR(<) -CPPAD_CG_OPERATOR( <=) - -template -inline bool operator !=(const CG &left, double right) { - if (left.isParameter()) { - return left.getValue() != right; - } else { - return true; - } -} - -} // END cg namespace -} // END CppAD namespace - -#endif - diff --git a/ct_core/include/ct/external/cppad/cg/cond_exp_op.hpp b/ct_core/include/ct/external/cppad/cg/cond_exp_op.hpp deleted file mode 100644 index abbff9f55..000000000 --- a/ct_core/include/ct/external/cppad/cg/cond_exp_op.hpp +++ /dev/null @@ -1,238 +0,0 @@ -#ifndef CPPAD_CG_COND_EXP_OP_INCLUDED -#define CPPAD_CG_COND_EXP_OP_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { - -namespace { - -/** - * Determine if two CG objects are equal - */ -template -inline bool isSameExpression(const cg::CG& trueCase, - const cg::CG& falseCase) { - return (trueCase.isParameter() && falseCase.isParameter() && - trueCase.getValue() == falseCase.getValue()) || - (trueCase.isVariable() && falseCase.isVariable() && - trueCase.getOperationNode() == falseCase.getOperationNode()); -} - -/** - * Get the code handler out of some CG objects - */ -template -inline cg::CodeHandler* findCodeHandler(const cg::CG& left, - const cg::CG& right, - const cg::CG& trueCase, - const cg::CG& falseCase) throw (cg::CGException) { - cg::CodeHandler* handler; - - cg::CodeHandler* lh = left.getCodeHandler(); - cg::CodeHandler* rh = right.getCodeHandler(); - cg::CodeHandler* th = trueCase.getCodeHandler(); - cg::CodeHandler* fh = falseCase.getCodeHandler(); - - if (!left.isParameter()) { - handler = lh; - } else if (!right.isParameter()) { - handler = rh; - } else if (!trueCase.isParameter()) { - handler = th; - } else if (!falseCase.isParameter()) { - handler = fh; - } else { - CPPAD_ASSERT_UNKNOWN(0); - throw cg::CGException("Unexpected error!"); - } - - if ((!right.isParameter() && rh != handler) - || (!trueCase.isParameter() && th != handler) - || (!falseCase.isParameter() && fh != handler)) { - throw cg::CGException("Attempting to use different source code generation handlers in the same source code generation"); - } - - return handler; -} - -} // END namespace - -/** - * Creates a conditional expression. - * INTERNAL ONLY - */ -template -inline cg::CG CondExp(cg::CGOpCode op, - const cg::CG& left, - const cg::CG& right, - const cg::CG& trueCase, - const cg::CG& falseCase, - bool (*compare)(const Base&, const Base&)) { - using namespace CppAD::cg; - - if (left.isParameter() && right.isParameter()) { - if (compare(left.getValue(), right.getValue())) - return trueCase; - else - return falseCase; - - - } else if (isSameExpression(trueCase, falseCase)) { - return trueCase; - } else { - - CodeHandler* handler = findCodeHandler(left, right, trueCase, falseCase); - - CG result(*handler->makeNode(op,{left.argument(), right.argument(), trueCase.argument(), falseCase.argument()})); - - if (left.isValueDefined() && right.isValueDefined()) { - if (compare(left.getValue(), right.getValue())) { - if (trueCase.isValueDefined()) { - result.setValue(trueCase.getValue()); - } - } else - if (falseCase.isValueDefined()) { - result.setValue(falseCase.getValue()); - } - } - - return result; - } - -} - -/** - * Creates a conditional expression for "less than" - */ -template -inline cg::CG CondExpLt(const cg::CG& left, - const cg::CG& right, - const cg::CG& trueCase, - const cg::CG& falseCase) { - - bool (*compare)(const Base&, const Base&) = [](const Base& l, const Base & r) { - return l < r; - }; - - return CondExp(cg::CGOpCode::ComLt, - left, right, - trueCase, falseCase, - compare); -} - -/** - * Creates a conditional expression for "less or equal" - */ -template -inline cg::CG CondExpLe(const cg::CG& left, - const cg::CG& right, - const cg::CG& trueCase, - const cg::CG& falseCase) { - bool (*comp)(const Base&, const Base&) = [](const Base& l, const Base & r) { - return l <= r; - }; - - return CondExp(cg::CGOpCode::ComLe, - left, right, - trueCase, falseCase, - comp); -} - -/** - * Creates a conditional expression for "equals" - */ -template -inline cg::CG CondExpEq(const cg::CG& left, - const cg::CG& right, - const cg::CG& trueCase, - const cg::CG& falseCase) { - bool (*comp)(const Base&, const Base&) = [](const Base& l, const Base & r) { - return l == r; - }; - - return CondExp(cg::CGOpCode::ComEq, - left, right, - trueCase, falseCase, - comp); -} - -/** - * Creates a conditional expression for "greater or equal" - */ -template -inline cg::CG CondExpGe(const cg::CG& left, - const cg::CG& right, - const cg::CG& trueCase, - const cg::CG& falseCase) { - bool (*comp)(const Base&, const Base&) = [](const Base& l, const Base & r) { - return l >= r; - }; - - return CondExp(cg::CGOpCode::ComGe, - left, right, - trueCase, falseCase, - comp); -} - -/** - * Creates a conditional expression for "greater than" - */ -template -inline cg::CG CondExpGt(const cg::CG& left, - const cg::CG& right, - const cg::CG& trueCase, - const cg::CG& falseCase) { - bool (*comp)(const Base&, const Base&) = [](const Base& l, const Base & r) { - return l > r; - }; - - return CondExp(cg::CGOpCode::ComGt, - left, right, - trueCase, falseCase, - comp); -} - -template -inline cg::CG CondExpOp(enum CompareOp cop, - const cg::CG& left, - const cg::CG& right, - const cg::CG& trueCase, - const cg::CG& falseCase) { - switch (cop) { - case CompareLt: - return CondExpLt(left, right, trueCase, falseCase); - - case CompareLe: - return CondExpLe(left, right, trueCase, falseCase); - - case CompareEq: - return CondExpEq(left, right, trueCase, falseCase); - - case CompareGe: - return CondExpGe(left, right, trueCase, falseCase); - - case CompareGt: - return CondExpGt(left, right, trueCase, falseCase); - - default: - CPPAD_ASSERT_UNKNOWN(0); - return trueCase; - } -} - -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/cppadcg.hpp b/ct_core/include/ct/external/cppad/cg/cppadcg.hpp deleted file mode 100644 index 5c5c683f2..000000000 --- a/ct_core/include/ct/external/cppad/cg/cppadcg.hpp +++ /dev/null @@ -1,254 +0,0 @@ -#ifndef CPPADCG_INCLUDED -#define CPPADCG_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -// -------------------------------------------------------------------------- -// System routines that can be used by rest of CppAD with out including - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -// --------------------------------------------------------------------------- -// operating system detection -#ifndef CPPAD_CG_SYSTEM_LINUX -# if defined(__linux__) || defined(__linux) || defined(linux) -# define CPPAD_CG_SYSTEM_LINUX 1 -# endif -#endif -#ifndef CPPAD_CG_SYSTEM_WIN -# if defined(_WIN32) || defined(_WIN64) || defined(__WIN32__) || defined(__TOS_WIN__) || defined(__WINDOWS__) -# define CPPAD_CG_SYSTEM_WIN 1 -# endif -#endif - -// --------------------------------------------------------------------------- -// all base type requirements -# include - -// --------------------------------------------------------------------------- -#include -#include -#include -#include - -// --------------------------------------------------------------------------- -// system dependent files -#include -#include - -// --------------------------------------------------------------------------- -// some utilities -#include -#include -#include - -// --------------------------------------------------------------------------- -// indexes -#include -#include -#include -#include -#include -#include -#include -#include - -// --------------------------------------------------------------------------- -// core files -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -// --------------------------------------------------------------------------- -#include -#include -#include -#include - -// --------------------------------------------------------------------------- -#include -#include - -// --------------------------------------------------------------------------- -// CppAD -#include - -// resolves some ambiguities -#include - -// addons -#include - -// --------------------------------------------------------------------------- -// additional utilities -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -// --------------------------------------------------------------------------- -// atomic function utilities -#include -#include -#include -#include -#include -#include - -// --------------------------------------------------------------------------- -// loop/pattern detection -#include -#include -#include -#include -#include -#include -#include -#include - -// --------------------------------------------------------------------------- -// C source code generation -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -// -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -// automated static library creation -#include -#include - -// compiler -#include -#include -#include -#include - -// model source code generation helpers -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -// automated dynamic library creation -#include -#include - -// --------------------------------------------------------------------------- -// automated dynamic library creation for Linux -#include -#include -#include - -#endif - diff --git a/ct_core/include/ct/external/cppad/cg/cppadcg_assert.hpp b/ct_core/include/ct/external/cppad/cg/cppadcg_assert.hpp deleted file mode 100644 index 5465c88ea..000000000 --- a/ct_core/include/ct/external/cppad/cg/cppadcg_assert.hpp +++ /dev/null @@ -1,43 +0,0 @@ -#ifndef CPPAD_CG_CPPADCG_ASSERT_INCLUDED -#define CPPAD_CG_CPPADCG_ASSERT_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#define CPPADCG_ASSERT_KNOWN(exp, msg) \ -{ if( ! ( exp ) ) \ - CppAD::ErrorHandler::Call( \ - true , \ - __LINE__ , \ - __FILE__ , \ - #exp , \ - msg ); \ -} - - -#ifdef NDEBUG -#define CPPADCG_ASSERT_UNKNOWN(exp) // do nothing -#else -#define CPPADCG_ASSERT_UNKNOWN(exp) \ -{ if( ! ( exp ) ) \ - CppAD::ErrorHandler::Call( \ - false , \ - __LINE__ , \ - __FILE__ , \ - #exp , \ - "" ); \ -} -#endif - -#endif diff --git a/ct_core/include/ct/external/cppad/cg/custom_position.hpp b/ct_core/include/ct/external/cppad/cg/custom_position.hpp deleted file mode 100644 index f879d3ba2..000000000 --- a/ct_core/include/ct/external/cppad/cg/custom_position.hpp +++ /dev/null @@ -1,117 +0,0 @@ -#ifndef CPPAD_CG_CUSTOM_POSITION_INCLUDED -#define CPPAD_CG_CUSTOM_POSITION_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Useful class for storing matrix indexes - */ -class CustomPosition { -private: - bool filterDefined_; - /// allowed elements - std::vector > elFilter_; - bool fullDefined_; - std::vector > elements_; -public: - - inline CustomPosition() : - filterDefined_(false), - fullDefined_(false) { - } - - template - inline CustomPosition(size_t m, size_t n, - const VectorSize& rows, - const VectorSize& cols) : - filterDefined_(true), - elFilter_(m, std::vector(n, false)), - fullDefined_(false) { - CPPADCG_ASSERT_KNOWN(rows.size() == cols.size(), "The number of row indexes must be the same as the number of column indexes."); - for (size_t i = 0; i < rows.size(); i++) { - elFilter_[rows[i]][cols[i]] = true; - } - } - - template - inline CustomPosition(size_t m, size_t n, - const VectorSet& elements) : - filterDefined_(true), - elFilter_(m, std::vector(n, false)), - fullDefined_(false) { - CPPADCG_ASSERT_KNOWN(elements.size() <= m, "Invalid number of rows."); - - for (size_t i = 0; i < elements.size(); i++) { - for (size_t it : elements[i]) { - elFilter_[i][it] = true; - } - } - } - - inline bool isFilterDefined() const { - return filterDefined_; - } - - inline bool isFullDefined() const { - return fullDefined_; - } - - inline void setFullElements(const std::vector >& elements) { - elements_ = elements; - filter(elements_); - fullDefined_ = true; - } - - inline const std::vector >& getFullElements()const { - return elements_; - } - - inline void filter(CppAD::vector >& sparsity) const { - ArrayWrapper > s(sparsity); - filter(s); - } - - inline void filter(std::vector >& sparsity) const { - ArrayWrapper > s(sparsity); - filter(s); - } - - inline void filter(ArrayWrapper >& sparsity) const { - if (!filterDefined_) - return; // nothing to do - - std::set::iterator it, currentIt; - - for (size_t i = 0; i < sparsity.size(); i++) { - it = sparsity[i].begin(); - while (it != sparsity[i].end()) { - // copy the current iterator then increment it - currentIt = it++; - if (!elFilter_[i][*currentIt]) { - sparsity[i].erase(currentIt); // not in allowed elements - } - } - } - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/augment_path.hpp b/ct_core/include/ct/external/cppad/cg/dae_index_reduction/augment_path.hpp deleted file mode 100644 index 945b38bd4..000000000 --- a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/augment_path.hpp +++ /dev/null @@ -1,65 +0,0 @@ -#ifndef CPPAD_CG_AUGMENTPATH_INCLUDED -#define CPPAD_CG_AUGMENTPATH_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include -#include -#include - -namespace CppAD { -namespace cg { - -/** - * Algorithm interface for assigning equations to variables in sorting - * procedures. - */ -template -class AugmentPath { -protected: - typedef CppAD::cg::CG CGBase; - typedef CppAD::AD ADCG; -protected: - SimpleLogger defaultLogger_; - // logger - SimpleLogger* logger_; -public: - inline AugmentPath() : - logger_(&defaultLogger_) { - } - - inline virtual ~AugmentPath() { - } - - /** - * - * @param i The equation node - * @return true if an augmented path was found - */ - virtual bool augmentPath(Enode& i) = 0; - - inline void setLogger(SimpleLogger& logger) { - logger_ = &logger; - } - - inline SimpleLogger& getLogger() const { - return *logger_; - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/augment_path_depth_lookahead.hpp b/ct_core/include/ct/external/cppad/cg/dae_index_reduction/augment_path_depth_lookahead.hpp deleted file mode 100644 index 96a2dc8a6..000000000 --- a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/augment_path_depth_lookahead.hpp +++ /dev/null @@ -1,85 +0,0 @@ -#ifndef CPPAD_CG_AUGMENTPATHDEPTHLOOKAHEAD_INCLUDED -#define CPPAD_CG_AUGMENTPATHDEPTHLOOKAHEAD_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include - -namespace CppAD { -namespace cg { - -/** - * An augment path algorithm based on MC21A. - * This procedure is depth-first search algorithm with an additional look ahead - * mechanism to find an unmatched variable for equation node before going - * deeper. - */ -template -class AugmentPathDepthLookahead : public AugmentPath { -protected: - typedef CppAD::cg::CG CGBase; - typedef CppAD::AD ADCG; -public: - - virtual bool augmentPath(Enode& i) override final { - i.color(this->logger_->log(), this->logger_->getVerbosity()); // avoids infinite recursion - - const std::vector*>& vars = i.variables(); - - // first look for derivative variables - for (Vnode* jj : vars) { - if (jj->antiDerivative() != nullptr && // not an algebraic variable - jj->assignmentEquation() == nullptr) { // not assigned yet - - jj->setAssignmentEquation(i, this->logger_->log(), this->logger_->getVerbosity()); - return true; - } - } - - // look for algebraic variables - for (Vnode* jj : vars) { - if (jj->antiDerivative() == nullptr && - jj->assignmentEquation() == nullptr) { // not assigned yet - - jj->setAssignmentEquation(i, this->logger_->log(), this->logger_->getVerbosity()); - return true; - } - } - - - for (Vnode* jj : vars) { - if (!jj->isColored()) { - jj->color(this->logger_->log(), this->logger_->getVerbosity()); - - Enode& k = *jj->assignmentEquation(); // all variables are assigned to another equation - if(!k.isColored()) { - bool pathFound = augmentPath(k); - if (pathFound) { - jj->setAssignmentEquation(i, this->logger_->log(), this->logger_->getVerbosity()); - return true; - } - } - } - } - - return false; - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/augment_path_depth_lookahead_a.hpp b/ct_core/include/ct/external/cppad/cg/dae_index_reduction/augment_path_depth_lookahead_a.hpp deleted file mode 100644 index b3eb185c6..000000000 --- a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/augment_path_depth_lookahead_a.hpp +++ /dev/null @@ -1,81 +0,0 @@ -#ifndef CPPAD_CG_AUGMENTPATHDEPTHLOOKAHEAD_A_INCLUDED -#define CPPAD_CG_AUGMENTPATHDEPTHLOOKAHEAD_A_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include - -namespace CppAD { -namespace cg { - -/** - * Similar algorithm as AugmentPathDepthLookahead which only considers - * the highest order derivatives and ignores algebraic variables. - * An augment path algorithm based on MC21A. - * This procedure is depth-first search algorithm with an additional look ahead - * mechanism to find an unmatched variable for equation node before going - * deeper. - */ -template -class AugmentPathDepthLookaheadA : public AugmentPath { -protected: - typedef CppAD::cg::CG CGBase; - typedef CppAD::AD ADCG; -public: - - virtual bool augmentPath(Enode & i) override final { - i.color(this->logger_->log(), this->logger_->getVerbosity()); // avoids infinite recursion - - const std::vector*>&vars = i.variables(); - - // first look for derivative variables - for (Vnode* jj : vars) { - if (jj->derivative() == nullptr && // highest order derivative - jj->antiDerivative() != nullptr && // not an algebraic variable - jj->assignmentEquation() == nullptr) { // not assigned yet - - jj->setAssignmentEquation(i, this->logger_->log(), this->logger_->getVerbosity()); - return true; - } - } - - for (Vnode* jj : vars) { - if (!jj->isColored() && - jj->derivative() == nullptr && // highest order derivative - jj->antiDerivative() != nullptr) { // not an algebraic variable - - Enode& k = *jj->assignmentEquation(); // all variables are assigned to another equation - - if (!k.isColored()) { - //jj->color(this->logger_->log(), this->logger_->getVerbosity()); // do not color variables! - - bool pathFound = augmentPath(k); - if (pathFound) { - jj->setAssignmentEquation(i, this->logger_->log(), this->logger_->getVerbosity()); - return true; - } - } - } - } - - return false; - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/bipartite_graph.hpp b/ct_core/include/ct/external/cppad/cg/dae_index_reduction/bipartite_graph.hpp deleted file mode 100644 index 653d7935b..000000000 --- a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/bipartite_graph.hpp +++ /dev/null @@ -1,1060 +0,0 @@ -#ifndef CPPAD_CG_BIPARTITE_GRAPH_INCLUDED -#define CPPAD_CG_BIPARTITE_GRAPH_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include -#include -#include - -namespace CppAD { -namespace cg { - -/** - * Bipartite graph which holds nodes to represent variables and equations - * in a DAE system. - */ -template -class BipartiteGraph { -protected: - typedef CppAD::cg::CG CGBase; - typedef CppAD::AD ADCG; -protected: - /** - * The original model - */ - ADFun >* const fun_; - /** - * DAE variable information for the original system - */ - std::vector varInfo_; - /** - * original sparsity pattern - */ - std::vector sparsity_; - // Bipartite graph ([equation i][variable j]) - std::vector*> vnodes_; - std::vector*> enodes_; - /** - * the maximum order of the time derivatives in the original model - */ - int origMaxTimeDivOrder_; - /** - * the number of time dependent variables in the original model - */ - size_t origTimeDependentCount_; - /** - * Defines whether or not original names saved by using - * CppAD::PrintFor(0, "", val, name) - * should be kept by also adding PrintFor operations in the reduced model. - */ - bool preserveNames_; -private: - int timeOrigVarIndex_; // time index in the original user model (may not exist) - SimpleLogger& logger_; -public: - - /** - * Creates the bipartite graph. - * - * @param fun The DAE model - * @param varInfo DAE model variable classification - * @param eqName Equation names (it can be an empty vector) - */ - BipartiteGraph(ADFun >& fun, - const std::vector& varInfo, - const std::vector& eqName, - SimpleLogger& logger) : - fun_(&fun), - varInfo_(varInfo), - origMaxTimeDivOrder_(0), - origTimeDependentCount_(0), - preserveNames_(false), - timeOrigVarIndex_(-1), - logger_(logger) { - - using namespace std; - using std::vector; - - CPPADCG_ASSERT_UNKNOWN(fun_ != nullptr); - const size_t m = fun.Range(); // equation count - const size_t n = fun.Domain(); // total variable count - - CPPADCG_ASSERT_UNKNOWN(varInfo_.size() == n); - for (size_t j = 0; j < n; ++j) { - varInfo_[j].setOriginalIndex(j); - varInfo_[j].setId(j); - } - - for (size_t j = 0; j < n; ++j) { - int deriv = varInfo_[j].getAntiDerivative(); - CPPADCG_ASSERT_UNKNOWN(deriv < int(varInfo_.size())); - if (deriv >= 0) { - varInfo_[deriv].setDerivative(j); - } - } - - for (size_t j = 0; j < n; ++j) { - determineVariableOrder(varInfo_[j]); - } - - // create equation nodes - enodes_.reserve(1.2 * m + 1); - enodes_.resize(m); - for (size_t i = 0; i < m; i++) { - if (i < eqName.size()) - enodes_[i] = new Enode(i, eqName[i]); - else - enodes_[i] = new Enode(i); - } - - // locate the time variable (if present) - for (size_t dj = 0; dj < n; dj++) { - if (varInfo_[dj].isIntegratedVariable()) { - if (timeOrigVarIndex_ >= 0) { - throw CGException("More than one time variable (integrated variable) defined"); - } - timeOrigVarIndex_ = dj; - } - } - - // determine the order of each time derivative - vector derivOrder = determineVariableDiffOrder(varInfo_); - map > order2Tape; - for (size_t tape = 0; tape < derivOrder.size(); ++tape) { - order2Tape[derivOrder[tape]].push_back(tape); - } - origMaxTimeDivOrder_ = *std::max_element(derivOrder.begin(), derivOrder.end()); - - /** - * generate names for the variables - */ - std::string timeVarName; - if (timeOrigVarIndex_ < 0) { - timeVarName = "t"; - } else { - if (varInfo_[timeOrigVarIndex_].getName().empty()) { - varInfo_[timeOrigVarIndex_].setName("t"); - } - timeVarName = varInfo_[timeOrigVarIndex_].getName(); - } - - stringstream ss; - for (int order = -1; order <= origMaxTimeDivOrder_; order++) { - //size_t j = 0; j < varInfo_.size(); j++ - const vector& tapeIndexes = order2Tape[order]; - if (order < 0) { - for (size_t p = 0; p < tapeIndexes.size(); ++p) { - DaeVarInfo& var = varInfo_[tapeIndexes[p]]; - if (var.getName().empty()) { - ss << "p" << p; - var.setName(ss.str()); - ss.str(""); - ss.clear(); - } - } - - } else if (order == 0) { - for (size_t p = 0; p < tapeIndexes.size(); ++p) { - DaeVarInfo& var = varInfo_[tapeIndexes[p]]; - if (var.getName().empty()) { - ss << "x" << p; - var.setName(ss.str()); - ss.str(""); - ss.clear(); - } - } - } else if (order > 0) { - for (size_t p = 0; p < tapeIndexes.size(); ++p) { - DaeVarInfo& var = varInfo_[tapeIndexes[p]]; - if (var.getName().empty()) { - const DaeVarInfo& deriv = varInfo_[var.getAntiDerivative()]; - var.setName("d" + deriv.getName() + "d" + timeVarName); - } - } - } - } - - // sort the variables according to the time derivative order (constants are kept out) - vector new2Tape; - vector tape2New(n, -1); - new2Tape.reserve(n); - for (int order = 0; order <= origMaxTimeDivOrder_; order++) { - const vector& tapeIndexes = order2Tape[order]; - for (size_t p = 0; p < tapeIndexes.size(); ++p) { - size_t tapeIndex = tapeIndexes[p]; - tape2New[tapeIndex] = new2Tape.size(); - new2Tape.push_back(tapeIndex); - } - } - - // create the variable nodes - origTimeDependentCount_ = new2Tape.size(); - vnodes_.resize(origTimeDependentCount_); - for (size_t j = 0; j < vnodes_.size(); j++) { - size_t tapeIndex = new2Tape[j]; - int tapeIndex0 = varInfo_[tapeIndex].getAntiDerivative(); - const std::string& name = varInfo_[tapeIndex].getName(); - - CPPADCG_ASSERT_UNKNOWN(varInfo_[tapeIndex].isFunctionOfIntegrated()); - - if (tapeIndex0 < 0) { - // generate the variable name - vnodes_[j] = new Vnode(j, tapeIndex, name); - } else { - Vnode* derivativeOf = vnodes_[tape2New[tapeIndex0]]; - vnodes_[j] = new Vnode(j, tapeIndex, derivativeOf, name); - } - } - - // create the edges - sparsity_ = jacobianSparsity, CGBase>(fun); - - for (size_t i = 0; i < m; i++) { - for (size_t p = 0; p < n; p++) { - int j = tape2New[p]; - if (j >= 0 && sparsity_[i * n + p]) { - enodes_[i]->addVariable(vnodes_[j]); - } - } - } - - // make sure the system is not under or over determined - size_t nvar = 0; - for (size_t j = 0; j < vnodes_.size(); j++) { - const Vnode* jj = vnodes_[j]; - if (!jj->isParameter() && // exclude constants - (jj->antiDerivative() != nullptr || // derivatives - jj->derivative() == nullptr) // algebraic variables - ) { - nvar++; - } - } - - if (nvar != m) { - throw CGException("The system is not well determined. " - "The of number of equations (", enodes_.size(), ")" - " does not match the number of unknown variables " - "(", nvar, ")."); - } - } - - BipartiteGraph(const BipartiteGraph& p) = delete; - - BipartiteGraph& operator=(const BipartiteGraph& p) = delete; - - virtual ~BipartiteGraph() { - for (size_t i = 0; i < enodes_.size(); i++) - delete enodes_[i]; - - for (size_t j = 0; j < vnodes_.size(); j++) - delete vnodes_[j]; - } - - - inline std::vector*>& variables() { - return vnodes_; - } - - inline const std::vector*>& variables() const { - return vnodes_; - } - - inline std::vector*>& equations() { - return enodes_; - } - - inline const std::vector*>& equations() const { - return enodes_; - } - - const std::vector& getOriginalVariableInfo() const { - return varInfo_; - } - - inline size_t getOrigTimeDependentCount() const { - return origTimeDependentCount_; - } - - /** - * Defines whether or not original names saved by using - * CppAD::PrintFor(0, "", val, name) - * should be kept by also adding PrintFor operations in the reduced model. - */ - void setPreserveNames(bool p) { - preserveNames_ = p; - } - - /** - * Whether or not original names saved by using - * CppAD::PrintFor(0, "", val, name) - * should be kept by also adding PrintFor operations in the reduced model. - */ - bool isPreserveNames() const { - return preserveNames_; - } - - /** - * Provides the structural index after this graph has been reduced. - * - * @return the DAE differentiation index. - */ - inline size_t getStructuralIndex() const { - size_t origM = this->fun_->Range(); - if (origM == enodes_.size()) { - // no index reduction performed: it is either an index 1 DAE or an ODE - bool isDAE = false; - for (size_t j = 0; j < varInfo_.size(); j++) { - const DaeVarInfo& jj = varInfo_[j]; - if (jj.getDerivative() < 0 && !jj.isIntegratedVariable() && jj.isFunctionOfIntegrated()) { - isDAE = true; // found algebraic variable - break; - } - } - if (!isDAE) { - return 0; - } else { - return 1; - } - } - - size_t index = 0; - for (size_t i = origM; i < enodes_.size(); i++) { - Enode* ii = enodes_[i]; - size_t eqOrder = 0; - if (ii->derivative() == nullptr) { - Enode* eq = ii; - while (eq->derivativeOf() != nullptr) { - eq = eq->derivativeOf(); - eqOrder++; - } - if (eqOrder > index) - index = eqOrder; - } - } - - return index + 1; // one extra differentiation to get an ODE - } - - inline void printResultInfo(const std::string& method) { - logger_.log() << "\n" << method << " DAE differentiation/structural index reduction:\n\n" - " Equations count: " << enodes_.size() << "\n"; - for (Enode* ii : enodes_) { - logger_.log() << " " << ii->index() << " - " << *ii << "\n"; - } - - logger_.log() << "\n Variable count: " << vnodes_.size() << "\n"; - - for (const Vnode* jj : vnodes_) { - logger_.log() << " " << jj->index() << " - " << *jj; - if (jj->assignmentEquation() != nullptr) { - logger_.log() << " assigned to " << *jj->assignmentEquation() << "\n"; - } else if (jj->isParameter()) { - logger_.log() << " is a parameter (time independent)\n"; - } else { - logger_.log() << " NOT assigned to any equation\n"; - } - } - - logger_.log() << "\n Degrees of freedom: " << vnodes_.size() - enodes_.size() << std::endl; - } - - inline void uncolorAll() { - for (Vnode* j : vnodes_) { - j->uncolor(); - } - - for (Enode* i : enodes_) { - i->uncolor(); - } - } - - inline Vnode* createDerivate(Vnode& j) { - if (j.derivative() != nullptr) - return j.derivative(); - - // add new variable derivatives of colored variables - size_t newVarCount = vnodes_.size() - origTimeDependentCount_; - size_t tapeIndex = varInfo_.size() + newVarCount; - - Vnode* jDiff = new Vnode (vnodes_.size(), tapeIndex, &j); - vnodes_.push_back(jDiff); - - if (logger_.getVerbosity() >= Verbosity::High) - logger_.log() << "Created " << *jDiff << "\n"; - - return jDiff; - } - - inline Enode* createDerivate(Enode& i, - bool addOrigVars = true) { - if (i.derivative() != nullptr) - return i.derivative(); - - Enode* iDiff = new Enode (enodes_.size(), &i); - enodes_.push_back(iDiff); - - // differentiate newI and create edges!!! - dirtyDifferentiateEq(i, *iDiff, addOrigVars); - - if (logger_.getVerbosity() >= Verbosity::High) - logger_.log() << "Created " << *iDiff << "\n"; - - return iDiff; - } - - /** - * Completely removes an equation and any variable that is only referenced - * by this equation from the graph. - * The equation cannot have a differentiated version of itself in the graph. - * - * @warning This equation node cannot be referenced after this call and - * neither can the variables which are also removed for not being present - * in any equation. - */ - inline void remove(const Enode& i) { - CPPADCG_ASSERT_UNKNOWN(enodes_[i.index()] == &i); - CPPADCG_ASSERT_UNKNOWN(i.derivative() == nullptr); - - for (Vnode* j: i.variables()) { - // remove the edges (connections in variables) - auto& eqs = j->equations(); - auto it = std::find(eqs.begin(), eqs.end(), &i); - CPPADCG_ASSERT_UNKNOWN(it != eqs.end()); - eqs.erase(it); - - /** - * remove variable - */ - while(j->equations().empty()) { - CPPADCG_ASSERT_UNKNOWN(vnodes_[j->index()] == j); - - if (j->derivative() == nullptr) { - vnodes_.erase(vnodes_.cbegin() + j->index()); - - // update variable indices - for (size_t jj = j->index(); jj < vnodes_.size(); ++jj) { - vnodes_[jj]->setTapeIndex(vnodes_[jj]->tapeIndex() - 1); - vnodes_[jj]->setIndex(vnodes_[jj]->index() - 1); - } - - auto* jOrig = j->antiDerivative(); - CPPADCG_ASSERT_UNKNOWN(jOrig != nullptr); - jOrig->setDerivative(nullptr); - - delete j; // no longer required - j = jOrig; - } - } - - } - - // update equation indices - for (size_t ii = i.index() + 1; ii < enodes_.size(); ++ii) { - CPPADCG_ASSERT_UNKNOWN(enodes_[ii]->index() > 0); - CPPADCG_ASSERT_UNKNOWN(enodes_[ii]->index() == ii); - enodes_[ii]->setIndex(enodes_[ii]->index() - 1); - } - - if(i.derivativeOf() != nullptr) { - i.derivativeOf()->setDerivative(nullptr); - } - - auto it = std::find(enodes_.begin(), enodes_.end(), &i); - CPPADCG_ASSERT_UNKNOWN(it != enodes_.end()); - enodes_.erase(it); - - delete &i; // no longer required - } - - /** - * Adds edges to a new equation resulting from the differentiation - * of another assuming the new equation differential contains - * all variables present in the original equation and their time - * derivatives (not exactly correct but it works because the - * potentially extra variables are removed later in the Pantelides method). - * - * An example with incorrectly added variables would be the dirty - * differentiation of: - * x1 + x2 == 0 - * wich include the variables [x1, dx1dt, x2, dx2dt] although it should - * only be [dx1dt, dx2dt]. - * - * @param i equation node to differentiate - * @throws CGException - */ - inline void dirtyDifferentiateEq(Enode& i, - Enode& iDiff, - bool addOrigVars = true) { - for (Vnode* jj : i.originalVariables()) { - if(addOrigVars) { - iDiff.addVariable(jj); - } - - if (jj->derivative() != nullptr) { - iDiff.addVariable(jj->derivative()); - } else if(!jj->isParameter()) { - iDiff.addVariable(createDerivate(*jj)); - } - } - } - - /** - * Creates a new tape for the index 1 model - */ - inline std::unique_ptr> generateNewModel(std::vector& newVarInfo, - std::vector& equationInfo, - const std::vector& x) { - using std::vector; - - std::unique_ptr > reducedFun; - - vector*> > newEquations; - - // find new equations that must be generated by differentiation - vector*> newEqs; - size_t origM = this->fun_->Range(); - for (size_t i = 0; i < origM; i++) { - if (enodes_[i]->derivative() != nullptr) { - CPPADCG_ASSERT_UNKNOWN(enodes_[i]->derivativeOf() == nullptr); - newEqs.push_back(enodes_[i]->derivative()); - } - } - - while (newEqs.size() > 0) { - newEquations.push_back(newEqs); - newEqs.clear(); - vector*>& eqs = newEquations.back(); - for (size_t i = 0; i < eqs.size(); i++) { - if (eqs[i]->derivative() != nullptr) { - newEqs.push_back(eqs[i]->derivative()); - } - } - } - - if (newEquations.empty()) { - // nothing to do - return nullptr; - } - - /** - * Add the relationship between variables and derivatives - */ - - /** - * Prepare the output information - */ - newVarInfo = varInfo_; // copy - size_t newVars = vnodes_.size() - origTimeDependentCount_; - newVarInfo.reserve(varInfo_.size() + newVars); - for (size_t j = origTimeDependentCount_; j < vnodes_.size(); j++) { - // new variable derivative added by the Pantelides method - Vnode* jj = vnodes_[j]; - CPPADCG_ASSERT_UNKNOWN(jj->antiDerivative() != nullptr); - size_t antiDeriv = jj->antiDerivative()->tapeIndex(); - size_t id = newVarInfo.size(); - newVarInfo.push_back(DaeVarInfo(antiDeriv, jj->name(), id)); // create the new variable - DaeVarInfo& newVar = newVarInfo.back(); - DaeVarInfo& newAntiDeriv = newVarInfo[antiDeriv]; - - newAntiDeriv.setDerivative(jj->tapeIndex()); // update the antiderivative - newVar.setOrder(newAntiDeriv.getOrder() + 1); - newVar.setOriginalAntiDerivative(newVar.getOrder() == 1 ? newAntiDeriv.getOriginalIndex() : newAntiDeriv.getOriginalAntiDerivative()); - if (jj->derivative() != nullptr) { - newVar.setDerivative(jj->derivative()->tapeIndex()); - } - } - - std::map*, Vnode*> assignments; - for (size_t j = 0; j < vnodes_.size(); j++) { - Vnode* jj = vnodes_[j]; - if (jj->assignmentEquation() != nullptr) { - assignments[jj->assignmentEquation()] = jj; - } - } - - equationInfo.resize(enodes_.size()); - for (size_t i = 0; i < enodes_.size(); i++) { - Enode* ii = enodes_[i]; - int derivativeOf = ii->derivativeOf() != nullptr ? ii->derivativeOf()->index() : -1; - int origIndex = ii->derivativeOf() == nullptr ? i : -1; - int assignedVarIndex = assignments.count(ii) > 0 ? assignments[ii]->tapeIndex() : -1; - - equationInfo[i] = DaeEquationInfo(i, origIndex, derivativeOf, assignedVarIndex); - } - - size_t timeTapeIndex; - { - CodeHandler handler; - - vector indep0(this->fun_->Domain()); - handler.makeVariables(indep0); - - const vector dep0 = forward0(*this->fun_, indep0); - - /** - * generate a new tape - */ - - vector indepNew; - if (timeOrigVarIndex_ >= 0) { - indepNew = vector(newVarInfo.size()); // variables + time (vnodes include time) - timeTapeIndex = timeOrigVarIndex_; - } else { - indepNew = vector(newVarInfo.size() + 1); // variables + time (new time variable added) - timeTapeIndex = indepNew.size() - 1; - } - - // initialize with the user provided values - for (size_t j = 0; j < x.size(); j++) { - indepNew[j] = x[j]; - } - Independent(indepNew); - - // variables with the relationship between x dxdt and t - vector indep2 = prepareTimeDependentVariables(indepNew, newVarInfo, timeTapeIndex); - indep2.resize(indep0.size()); - - Evaluator evaluator0(handler); - evaluator0.setPrintFor(preserveNames_); // variable names saved with CppAD::PrintFor - vector depNew = evaluator0.evaluate(indep2, dep0); - depNew.resize(enodes_.size()); - - try { - reducedFun.reset(new ADFun(indepNew, depNew)); - } catch (const std::exception& ex) { - throw CGException("Failed to create ADFun: ", ex.what()); - } - - if (logger_.getVerbosity() >= Verbosity::High) { - logger_.log() << "Original model:\n"; - printModel(logger_.log(), *reducedFun, newVarInfo, equationInfo); - } - } - - - /** - * generate the system of equations by repeatedly differentiating - * and adding equations to the DAE system - */ - for (size_t d = 0; d < newEquations.size(); d++) { - vector*>& equations = newEquations[d]; - - size_t m = reducedFun->Domain(); // total variable count - //size_t n = reducedFun->Range(); // equation count - - /** - * register operations from the other equations - */ - CodeHandler handler0; - - vector indep0(m); - handler0.makeVariables(indep0); - - vector dep = forward0(*reducedFun, indep0); - - /** - * register operations used to differentiate the equations - */ - //forwardTimeDiff(equations, dep, timeTapeIndex); - reverseTimeDiff(*reducedFun, equations, dep, timeTapeIndex); - - /** - * reconstruct the new system of equations - */ - vector indep2; - vector indepNew; - - if (d < newEquations.size() - 1) { - indepNew.resize(m); - } else if (timeOrigVarIndex_ < 0) { - // the very last model creation - indepNew.resize(m - 1); // take out time (it was added by this function and not the user) - } else { - // the very last model creation - indepNew.resize(m); - } - - for (size_t j = 0; j < x.size(); j++) { - indepNew[j] = x[j]; - } - Independent(indepNew); - - if (d < newEquations.size() - 1) { - // variables with the relationship between x, dxdt and t - indep2 = prepareTimeDependentVariables(indepNew, newVarInfo, timeTapeIndex); - } else { - indep2 = indepNew; - indep2.resize(m); - } - - Evaluator evaluator(handler0); - evaluator.setPrintFor(preserveNames_); // variable names saved with CppAD::PrintFor - vector depNew = evaluator.evaluate(indep2, dep); - - try { - reducedFun.reset(new ADFun(indepNew, depNew)); - } catch (const std::exception& ex) { - throw CGException("Failed to create ADFun: ", ex.what()); - } - - if (logger_.getVerbosity() >= Verbosity::High) { - logger_.log() << equations.size() << " new equations:\n"; - printModel(logger_.log(), *reducedFun, newVarInfo, equationInfo); - } - } - - return reducedFun; - } - - inline static void forwardTimeDiff(ADFun& reducedFun, - const std::vector*>& equations, - std::vector >& dep, - size_t tapeTimeIndex) { - - size_t m = reducedFun.Domain(); - - std::vector u(m, CGBase(0)); - u[tapeTimeIndex] = CGBase(1); - std::vector v; - try { - v = reducedFun.Forward(1, u); - } catch (const std::exception& ex) { - throw CGException("Failed to determine model Jacobian (forward mode): ", ex.what()); - } - - for (size_t e = 0; e < equations.size(); e++) { - dep[equations[e]->index()] = v[equations[e]->derivativeOf()->index()]; - } - } - - inline static void reverseTimeDiff(ADFun& reducedFun, - const std::vector*>& equations, - std::vector >& dep, - size_t tapeTimeIndex) { - size_t m = reducedFun.Domain(); - size_t n = reducedFun.Range(); - std::vector u(m); - std::vector v(n); - - for (size_t e = 0; e < equations.size(); e++) { - size_t i = equations[e]->derivativeOf()->index(); - if (reducedFun.Parameter(i)) { // return zero for this component of f - dep[equations[e]->index()] = 0; - } else { - // set v to the i-th coordinate direction - v[i] = 1; - - // compute the derivative of this component of f - try { - u = reducedFun.Reverse(1, v); - } catch (const std::exception& ex) { - throw CGException("Failed to determine model Jacobian (reverse mode): ", ex.what()); - } - - // reset v to vector of all zeros - v[i] = 0; - - // return the result - dep[equations[e]->index()] = u[tapeTimeIndex]; - } - } - } - - /** - * Introduces a dependency with respect to time in the provided variables. - * - * @param indepOrig The variables without time dependency - * (in the original variable order). - * @return The new variables with the time dependency - * (in the original variable order). - */ - inline std::vector > > prepareTimeDependentVariables(const std::vector& indepOrig, - const std::vector& newVarInfo, - size_t timeTapeIndex) const { - CPPADCG_ASSERT_UNKNOWN(timeTapeIndex < indepOrig.size()); - - using std::vector; - typedef CppAD::AD ADCGBase; - - vector indepOut(indepOrig.size()); - vector ax(3); // function inputs - vector ay(1); // function output - - ax[2] = indepOrig[timeTapeIndex]; // time - - for (size_t j = 0; j < newVarInfo.size(); j++) { - const DaeVarInfo& jj = newVarInfo[j]; - if (jj.getDerivative() >= 0) { - ax[0] = indepOrig[j]; // x - ax[1] = indepOrig[jj.getDerivative()]; // dxdt - time_var(0, ax, ay); - indepOut[j] = ay[0]; - } else { - indepOut[j] = indepOrig[j]; - } - } - - if (newVarInfo.size() < indepOrig.size()) { - indepOut[indepOut.size() - 1] = indepOrig[timeTapeIndex]; - } - - return indepOut; - } - - inline void printModel(std::ostream& out, - ADFun >* fun) { - printModel(out, fun, varInfo_); - } - - /** - * Prints out a DAE model to the standard output. - * - * @param fun The taped model - */ - inline void printModel(std::ostream& out, - ADFun >& fun, - const std::vector& varInfo, - const std::vector& eqInfo) const { - std::vector vnames(varInfo.size()); - for (size_t i = 0; i < varInfo.size(); ++i) { - vnames[i] = varInfo[i].getName(); - } - std::vector eqnames(eqInfo.size()); - for (size_t i = 0; i < eqInfo.size(); ++i) { - if(eqInfo[i].isExplicit()) { - CPPADCG_ASSERT_UNKNOWN(eqInfo[i].getAssignedVarIndex() >= 0); - eqnames[i] = "d" + varInfo[eqInfo[i].getAssignedVarIndex()].getName() + "dt"; - } else { - eqnames[i] = "res[" + std::to_string(i) + "]"; - } - } - - printModel(out, fun, vnames, eqnames); - } - - /** - * Prints out a DAE model to the standard output. - * - * @param fun The taped model - * @param indepNames The independent variable names - * @param depNames The dependent variable names - */ - inline void printModel(std::ostream& out, - ADFun >& fun, - const std::vector& indepNames, - const std::vector& depNames = std::vector()) const { - using std::vector; - - CPPADCG_ASSERT_UNKNOWN(fun.Domain() == indepNames.size() || fun.Domain() == indepNames.size() + 1); // with or without time - - CodeHandler handler; - - vector indep0(fun.Domain()); - handler.makeVariables(indep0); - - vector dep0 = forward0(fun, indep0); - - LanguageC langC("double"); - - /** - * generate the source code - */ - LangCCustomVariableNameGenerator nameGen(depNames, indepNames, "res"); - - std::ostringstream code; - handler.generateCode(code, langC, dep0, nameGen); - out << "\n" << code.str() << std::endl; - } - - inline void printDot(std::ostream& out) const { - out << "digraph {\n"; - out << " overlap=false\n"; - out << " rankdir=LR\n"; - out << " node [style=filled, fillcolor=\"#bdcef5\", color=\"#17128e\"]\n"; - out << " edge [splines=false, dir=none]\n"; - - // variables - out << " subgraph variables {\n"; - out << " rank=min\n"; - for (const Vnode* j : vnodes_) { - if(!j->isDeleted()) { - out << " v" << j->index() << " [label=\"" << j->name() << "\""; - if (j->isColored()) - out << ", color=\"#17c68e\""; - out << "]\n"; - } - } - out << " }\n"; - - // equations - out << " subgraph equations {\n"; - out << " rank=max\n"; - for (const Enode* i : enodes_) { - out << " e" << i->index() << " [label=\"" << i->name() << "\""; - if (i->isColored()) - out << ", color=\"#17c68e\""; - out << "]\n"; - } - out << " }\n"; - - // derivatives of equations - out << " subgraph eq_derivatives {\n"; - out << " edge[dir=forward, color=grey]\n"; - for (const Enode* i : enodes_) { - if (i->derivative() != nullptr && i->derivativeOf() == nullptr) { - while (i->derivative() != nullptr) { - out << " e" << i->index() << ":e -> e" << i->derivative()->index() << ":e\n"; - i = i->derivative(); - } - } - } - out << " }\n"; - - // derivatives of variables - out << " subgraph var_derivatives {\n"; - out << " edge[dir=forward, color=grey]\n"; - for (const Vnode* j : vnodes_) { - if (!j->isDeleted() && j->derivative() != nullptr && (j->antiDerivative() == nullptr || j->antiDerivative()->isDeleted())) { - if (!j->derivative()->isDeleted()) { - while (j->derivative() != nullptr && !j->derivative()->isDeleted()) { - out << " v" << j->index() << ":w -> v" << j->derivative()->index() << ":w\n"; - j = j->derivative(); - } - } - } - } - out << " }\n"; - - // edges - for (const Enode* i : enodes_) { - bool added = false; - for (const Vnode* j : i->originalVariables()) { - if (!j->isDeleted() && j->assignmentEquation() != i) { - if(!added) { - out << " "; - added = true; - } - out << "e" << i->index() << " -> v" << j->index() << " "; - } - } - if (added) - out << "\n"; - } - - out << " subgraph assigned {\n"; - out << " edge[color=blue,penwidth=3.0,style=dashed]\n"; - for (const Enode* i : enodes_) { - bool added = false; - - for (const Vnode* j : i->originalVariables()) { - if (!j->isDeleted() && j->assignmentEquation() == i) { - if(!added) { - out << " "; - added = true; - } - out << "e" << i->index() << " -> v" << j->index() << " "; - } - } - - if (added) - out << "\n"; - } - - out << " }\n"; - out << "}\n"; - } - - template - inline VectorCGB forward0(ADFun& fun, - const VectorCGB& indep0) const { - - if (preserveNames_) { - // stream buffer is used to reload names saved with CppAD::PrintFor() - OperationNodeNameStreambuf b; - std::ostream out(&b); - - return fun.Forward(0, indep0, out); - } else { - return fun.Forward(0, indep0); - } - } - - static inline std::vector determineVariableDiffOrder(const std::vector& varInfo) { - size_t n = varInfo.size(); - // determine the order of each time derivative - std::vector derivOrder(n, 0); - for (size_t dj = 0; dj < n; dj++) { - size_t j0; - derivOrder[dj] = determineVariableDiffOrder(varInfo, dj, j0); - } - - return derivOrder; - } - - static inline int determineVariableDiffOrder(const std::vector& varInfo, size_t index, size_t& j0) { - int derivOrder = -1; - j0 = index; - if (varInfo[index].isFunctionOfIntegrated()) { - derivOrder = 0; - while (varInfo[j0].getAntiDerivative() >= 0) { - CPPADCG_ASSERT_UNKNOWN(j0 < varInfo.size()); - CPPADCG_ASSERT_UNKNOWN(varInfo[j0].isFunctionOfIntegrated()); - derivOrder++; - j0 = varInfo[j0].getAntiDerivative(); - } - } - - return derivOrder; - } - -private: - inline void determineVariableOrder(DaeVarInfo& var) { - if (var.getAntiDerivative() >= 0) { - DaeVarInfo& antiD = varInfo_[var.getAntiDerivative()]; - if (antiD.getOriginalAntiDerivative() < 0) { - determineVariableOrder(antiD); - } - var.setOrder(antiD.getOrder() + 1); - var.setOriginalAntiDerivative(var.getOrder() == 1 ? antiD.getOriginalIndex() : antiD.getOriginalAntiDerivative()); - } - } -}; - -template -inline std::ostream& operator<<(std::ostream& os, - const BipartiteGraph& g) { - for (const Enode* i : g.equations()) { - for (const Vnode* j : i->originalVariables()) { - os << i->name(); - if (j->isDeleted()) { - os << "~~"; - } else if (j->assignmentEquation() == i) { - os << "=="; - } else { - os << "--"; - } - os << j->name() << " "; - } - os << std::endl; - } - - return os; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/bipartite_nodes.hpp b/ct_core/include/ct/external/cppad/cg/dae_index_reduction/bipartite_nodes.hpp deleted file mode 100644 index f2597413d..000000000 --- a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/bipartite_nodes.hpp +++ /dev/null @@ -1,426 +0,0 @@ -#ifndef CPPAD_CG_BIPARTITE_NODES_INCLUDED -#define CPPAD_CG_BIPARTITE_NODES_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include -#include -#include -#include -#include - -namespace CppAD { -namespace cg { - -/** - * Bipartite graph node - */ -template -class BiPGraphNode { -protected: - size_t index_; // location of node - bool colored_; // node visited -public: - - inline BiPGraphNode(size_t index) : - index_(index), - colored_(false) { - } - - inline void color(std::ostream& out = std::cout, - Verbosity verbosity = Verbosity::None) { - colored_ = true; - - if (verbosity >= Verbosity::High) - out << " Colored " << nodeType() << " " << name() << "\n"; - } - - inline void uncolor() { - colored_ = false; - } - - inline bool isColored() const { - return colored_; - } - - inline size_t index() const { - return index_; - } - - inline void setIndex(size_t index) { - index_ = index; - } - - virtual const std::string& name() const = 0; - - virtual std::string nodeType() = 0; - - inline virtual ~BiPGraphNode() { - } -}; - -template -class Vnode; // forward declaration - -/** - * Equation nodes - */ -template -class Enode : public BiPGraphNode { -protected: - static const std::string TYPE; - /** - * Original variables present in this equation. - * A vector is used instead of a set to ensure reproducibility. - */ - std::vector*> vnodes_orig_; - /** - * Variables present in this equation which where not deleted. - * A vector is used instead of a set to ensure reproducibility. - */ - std::vector*> vnodes_; - /** - * the differentiated equation used to produce this one - * (B in Pantelides algorithm) - */ - Enode* differentiation_; - /** - * Original equation which was differentiated - */ - Enode* differentiationOf_; - /** - * - */ - Vnode* assign_; - /** - * A name for the equation - */ - std::string name_; -public: - - inline Enode(size_t index, - const std::string& name = "") : - BiPGraphNode(index), - differentiation_(nullptr), - differentiationOf_(nullptr), - assign_(nullptr), - name_(name.empty()? ("Eq" + std::to_string(index)) : name) { - } - - inline Enode(size_t index, - Enode* differentiationOf) : - BiPGraphNode(index), - differentiation_(nullptr), - differentiationOf_(differentiationOf), - assign_(nullptr), - name_("Diff(" + differentiationOf->name() + ")") { - differentiationOf_->setDerivative(this); - } - - inline virtual ~Enode() { - } - - inline const std::vector*>& variables() const { - return vnodes_; - } - - inline const std::vector*>& originalVariables() const { - return vnodes_orig_; - } - - inline void addVariable(Vnode* j) { - if (std::find(vnodes_orig_.begin(), vnodes_orig_.end(), j) == vnodes_orig_.end()) { - vnodes_orig_.push_back(j); - if (!j->isDeleted()) { - vnodes_.push_back(j); - j->addEquation(this); - } - } - } - - inline Vnode* assignmentVariable() const { - return assign_; - } - - inline void setAssigmentVariable(Vnode& j) { - assign_ = &j; - } - - /** - * @return the equation that was derived by differentiating this - * equation - */ - inline Enode* derivative() const { - return differentiation_; - } - - inline Enode* derivativeOf() const { - return differentiationOf_; - } - - inline Enode* originalEquation() { - if (differentiationOf_ == nullptr) { - return this; - } else { - return differentiationOf_->originalEquation(); - } - } - - inline void deleteNode(Vnode* j) { - auto it = std::find(vnodes_.begin(), vnodes_.end(), j); - if (it != vnodes_.end()) - vnodes_.erase(it); - } - - inline void setDerivative(Enode* difEq) { - differentiation_ = difEq; - } - - virtual const std::string& name() const { - return name_; - } - - virtual std::string nodeType() { - return TYPE; - } -}; - -template -inline std::ostream& operator <<(std::ostream& os, const Enode& i) { - if (i.derivativeOf() != nullptr) { - os << "Diff(" << *i.derivativeOf() << ")"; - } else { - os << "Equation " << i.name() << " (" << i.index() << ")"; - } - - return os; -} - -template -const std::string Enode::TYPE = "Equation"; - -/** - * Variable nodes - */ -template -class Vnode : public BiPGraphNode { -protected: - static const std::string TYPE; - /** - * - */ - bool deleted_; - /** - * Whether or not this variable is time dependent - */ - bool parameter_; - /** - * Equations that use this variable. - * A vector is used instead of a set to ensure reproducibility. - */ - std::vector*> enodes_; - /** - * - */ - Enode* assign_; - /** - * the time derivative variable of this variable - * (A in Pantelides algorithm) - */ - Vnode* derivative_; - /** - * the variable which was differentiated to create this one - */ - Vnode* const antiDerivative_; - /** - * The index in the tape - */ - size_t tapeIndex_; - /** - * name - */ - std::string name_; - -public: - - inline Vnode(size_t index, - int tapeIndex, - const std::string& name) : - BiPGraphNode(index), - deleted_(false), - parameter_(false), - assign_(nullptr), - derivative_(nullptr), - antiDerivative_(nullptr), - tapeIndex_(tapeIndex), - name_(name) { - - } - - inline Vnode(size_t index, - size_t tapeIndex, - Vnode* derivativeOf, - const std::string& name = "") : - BiPGraphNode(index), - deleted_(false), - parameter_(false), - assign_(nullptr), - derivative_(nullptr), - antiDerivative_(derivativeOf), - tapeIndex_(tapeIndex), - name_(name.empty() ? "d" + derivativeOf->name() + "dt" : name) { - CPPADCG_ASSERT_UNKNOWN(antiDerivative_ != nullptr); - - antiDerivative_->setDerivative(this); - } - - inline virtual ~Vnode() { - } - - inline virtual const std::string& name() const { - return name_; - } - - inline size_t tapeIndex() const { - return tapeIndex_; - } - - inline void setTapeIndex(size_t tapeIndex) { - tapeIndex_ = tapeIndex; - } - - inline std::vector*>& equations() { - return enodes_; - } - - inline const std::vector*>& equations() const { - return enodes_; - } - - /** - * @return the time derivative variable - */ - inline Vnode* derivative() const { - return derivative_; - } - - /** - * @return the variable which was differentiated to create this one - */ - inline Vnode* antiDerivative() const { - return antiDerivative_; - } - - inline Vnode* originalVariable() { - if (antiDerivative_ == nullptr) { - return this; - } else { - return antiDerivative_->originalVariable(); - } - } - - inline Vnode* originalVariable(size_t origVarSize) { - if (antiDerivative_ == nullptr || this->index_ < origVarSize) { - return this; - } else { - return antiDerivative_->originalVariable(); - } - } - - inline bool isDeleted() const { - return deleted_; - } - - inline void makeParameter(std::ostream& out = std::cout, - Verbosity verbosity = Verbosity::None) { - parameter_ = true; - deleteNode(out, verbosity); - } - - inline bool isParameter() const { - return parameter_; - } - - inline void deleteNode(std::ostream& out = std::cout, - Verbosity verbosity = Verbosity::None) { - if (verbosity >= Verbosity::High) - out << "Deleting " << *this << "\n"; - - deleted_ = true; - for (Enode* i : enodes_) { - i->deleteNode(this); - } - enodes_.clear(); - } - - inline Enode* assignmentEquation() const { - return assign_; - } - - inline void setAssignmentEquation(Enode& i, - std::ostream& out = std::cout, - Verbosity verbosity = Verbosity::None) { - if (verbosity >= Verbosity::High) - out << " Assigning " << *this << " to " << i << "\n"; - - assign_ = &i; - i.setAssigmentVariable(*this); - } - - virtual std::string nodeType() { - return TYPE; - } - - inline void setDerivative(Vnode* div) { - derivative_ = div; - } - - unsigned int order() const { - if (antiDerivative_ == nullptr) { - return 0u; - } else { - return antiDerivative_->order() + 1u; - } - } - -protected: - - inline void addEquation(Enode* i) { - if (!deleted_) { - CPPADCG_ASSERT_UNKNOWN(std::find(enodes_.begin(), enodes_.end(), i) == enodes_.end()); - enodes_.push_back(i); - } - } - - friend class Enode; -}; - -template -inline std::ostream& operator <<(std::ostream& os, const Vnode& j) { - if (j.antiDerivative() != nullptr) { - os << "Diff(" << *j.antiDerivative() << ")"; - } else { - os << "Variable " << j.name(); - } - return os; -} - -template -const std::string Vnode::TYPE = "Variable"; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dae_equation_info.hpp b/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dae_equation_info.hpp deleted file mode 100644 index b31e69fd8..000000000 --- a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dae_equation_info.hpp +++ /dev/null @@ -1,120 +0,0 @@ -#ifndef CPPAD_CG_DAE_EQUATION_INFO_HPP -#define CPPAD_CG_DAE_EQUATION_INFO_HPP -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - - -namespace CppAD { -namespace cg { - -/** - * DAE equation information - */ -class DaeEquationInfo { -private: - /** - * A unique identifier for this equation (used internally) - */ - size_t id_; - /** - * The equation index in the original user model - */ - int originalIndex_; - /** - * The index of the equation that was differentiated to obtain this - * equation. A negative value means that the current equation isn't a - * differentiation of an existing equation. - */ - int antiDerivative_; - /** - * The variable index associated with this equation. A negative value is - * used if this equation does not have an assigned variable. - */ - int assignedVarIndex_; - /** - * Whether or not if it is an explicit differential equation - */ - bool explicit_; -public: - - inline DaeEquationInfo() : - id_(0), - originalIndex_(-1), - antiDerivative_(-1), - assignedVarIndex_(-1), - explicit_(false) { - } - - inline DaeEquationInfo(size_t id, - int originalIndex, - int derivativeOf, - int assignedVarIndex, - bool explicitEq = false) : - id_(id), - originalIndex_(originalIndex), - antiDerivative_(derivativeOf), - assignedVarIndex_(assignedVarIndex), - explicit_(explicitEq) { - } - - /** - * Provides a unique identifier for the equation. - * - * @return a unique identifier for the equation. - */ - inline size_t getId() const { - return id_; - } - - inline void setId(size_t id) { - id_ = id; - } - - inline int getAntiDerivative() const { - return antiDerivative_; - } - - inline void setAntiDerivative(int derivativeOf) { - antiDerivative_ = derivativeOf; - } - - inline int getAssignedVarIndex() const { - return assignedVarIndex_; - } - - inline void setAssignedVarIndex(int assignedVarIndex) { - assignedVarIndex_ = assignedVarIndex; - } - - inline int getOriginalIndex() const { - return originalIndex_; - } - - inline bool isExplicit() const { - return explicit_; - } - - inline void setExplicit(bool explicitEq) { - explicit_ = explicitEq; - } - - inline virtual ~DaeEquationInfo() { - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dae_index_reduction.hpp b/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dae_index_reduction.hpp deleted file mode 100644 index 475ca1705..000000000 --- a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dae_index_reduction.hpp +++ /dev/null @@ -1,76 +0,0 @@ -#ifndef CPPAD_CG_DAE_INDEX_REDUCTION_INCLUDED -#define CPPAD_CG_DAE_INDEX_REDUCTION_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include -#include -#include -#include - -namespace CppAD { -namespace cg { - -/** - * Base class for algorithms that perform automatic index reduction of - * implicit DAEs. - */ -template -class DaeIndexReduction : public SimpleLogger { -protected: - /** - * The original model representing an implicit DAE system - */ - ADFun >* const fun_; -public: - - /** - * Creates a new algorithm for index reduction of DAE systems. - * - * @param fun The original model (potentially high index) - */ - DaeIndexReduction(ADFun >& fun) : - fun_(&fun) { - } - - inline virtual ~DaeIndexReduction() { - } - - /** - * Provides the original model with a representation of an implicit DAE - * (potentially high index). - */ - inline ADFun >& getOriginalModel() const { - return *fun_; - } - - /** - * Performs the DAE index reduction and creates a new reduced index model. - * - * @param newVarInfo Variable related information of the reduced index model - * @param equationInfo Equation related information of the reduced index model - * @return the reduced index model - * (null if there was no need for index reduction) - */ - virtual std::unique_ptr>> reduceIndex(std::vector& newVarInfo, - std::vector& equationInfo) = 0; - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif - diff --git a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dae_structural_index_reduction.hpp b/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dae_structural_index_reduction.hpp deleted file mode 100644 index 01ce2be77..000000000 --- a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dae_structural_index_reduction.hpp +++ /dev/null @@ -1,99 +0,0 @@ -#ifndef CPPAD_CG_DAE_STRUCTURAL_INDEX_REDUCTION_INCLUDED -#define CPPAD_CG_DAE_STRUCTURAL_INDEX_REDUCTION_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include -#include - -namespace CppAD { -namespace cg { - -/** - * Base class for algorithms that perform automatic - * structural index reduction of implicit DAEs using graphs. - */ -template -class DaeStructuralIndexReduction : public DaeIndexReduction { -protected: - typedef CppAD::cg::CG CGBase; - typedef CppAD::AD ADCG; -protected: - // - BipartiteGraph graph_; -public: - - /** - * Creates a new algorithm for structural index reduction of DAE systems. - * - * @param fun The original model (potentially high index) - * @param varInfo The DAE system variable information (in the same order - * as in the tape) - * @param eqName Equation names (it can be an empty vector) - */ - DaeStructuralIndexReduction(ADFun>& fun, - const std::vector& varInfo, - const std::vector& eqName) : - DaeIndexReduction(fun), - graph_(fun, varInfo, eqName, *this) { - } - - inline virtual ~DaeStructuralIndexReduction() { - } - - inline BipartiteGraph& getGraph() { - return graph_; - } - - inline const BipartiteGraph& getGraph() const { - return graph_; - } - - /** - * Defines whether or not original names saved by using - * CppAD::PrintFor(0, "", val, name) - * should be kept by also adding PrintFor operations in the reduced model. - */ - inline void setPreserveNames(bool p) { - graph_.setPreserveNames(p); - } - - /** - * Whether or not original names saved by using - * CppAD::PrintFor(0, "", val, name) - * should be kept by also adding PrintFor operations in the reduced model. - */ - inline bool isPreserveNames() const { - return graph_.isPreserveNames(); - } - - /** - * Provides the structural index which is typically a good approximation of - * the differentiation index. - * It can only be called after reduceIndex(). - * - * @return the DAE structural index. - * @throws CGException - */ - inline size_t getStructuralIndex() const { - return graph_.getStructuralIndex(); - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif - diff --git a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dae_var_info.hpp b/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dae_var_info.hpp deleted file mode 100644 index 2df2ebfe8..000000000 --- a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dae_var_info.hpp +++ /dev/null @@ -1,324 +0,0 @@ -#ifndef CPPAD_CG_DAE_VAR_INFO_INCLUDED -#define CPPAD_CG_DAE_VAR_INFO_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * DAE variable information - */ -class DaeVarInfo { -private: - /** - * A unique identifier for this variable (used internally) - */ - size_t id_; - /** - * The index of the variable for which this variable is the time - * derivative. A negative value means that the current variable isn't - * a time derivative. - */ - int antiDerivative_; - /** - * The index of the time derivative of this variable. A negative value - * means that there is none. - */ - int derivative_; - /** - * Defines the independent variables that dependent on the integrated - * variable - */ - bool integratedDependent_; - /** - * Whether or not this variable is an integrated variable (usually - * associated with time) - */ - bool integratedVariable_; - /** - * A custom variable name (keep it empty to use an automatically - * generated name) - */ - std::string name_; - /** - * The variable tape index in the original model - */ - int originalIndex_; - /** - * Time derivative order. A negative value means that it is a constant. - * An order higher than zero does not mean that the variable should be - * treated as a differential variable. - */ - int order_; - /** - * The original variable index for which this variable is the - * time derivative (with the order provided by order_). A negative value - * means that the current variable was never a time derivative. - */ - int originalAntiDerivative_; -public: - - /** - * Creates a new DAE variable - * - * @param name A custom variable name (keep it empty to use an - * automatically generated name) - * @param id A unique identifier for this variable (used internally) - */ - inline DaeVarInfo(const std::string& name = "", - size_t id = 0) : - id_(id), - antiDerivative_(-1), - derivative_(-1), - integratedDependent_(true), - integratedVariable_(false), - name_(name), - originalIndex_(-1), - order_(0), - originalAntiDerivative_(-1) { - } - - inline DaeVarInfo(int derivativeOf, - const std::string& name = "", - size_t id = 0) : - id_(id), - antiDerivative_(derivativeOf), - derivative_(-1), - integratedDependent_(true), - integratedVariable_(false), - name_(name), - originalIndex_(-1), - order_(0), - originalAntiDerivative_(-1) { - } - - /** - * Provides a unique identifier for the variable. - * - * @return a unique identifier for the variable. - */ - inline size_t getId() const { - return id_; - } - - inline void setId(size_t id) { - id_ = id; - } - - /** - * The index of the variable that the current variable is the derivative - * of. A negative value means that the current variable isn't a - * derivative. - * - * @return The index of the variable for which this variable is the - * derivative of. - */ - inline int getAntiDerivative() const { - return antiDerivative_; - } - - inline void setAntiDerivative(int derivativeOf) { - antiDerivative_ = derivativeOf; - } - - /** - * The index of the time derivative for this variable. A negative value - * means that there is none. - * - * @return The index of the time derivative for this variable. - */ - inline int getDerivative() const { - return derivative_; - } - - /** - * Defines the index of the time derivative for this variable. - * - * @param derivative The index of the time derivative for this variable. - * A negative value means that there is none. - */ - inline void setDerivative(int derivative) { - derivative_ = derivative; - } - - /** - * Determines whether or not this variable depends on the - * independent/integrated variables. - * - * @return true if it is a parameter that does not depend on the - * integrated variables - */ - inline bool isFunctionOfIntegrated() const { - return integratedDependent_; - } - - /** - * Defines this variable as a parameter/constant that does not depend on - * the independent/integrated variables - */ - inline void makeConstant() { - integratedVariable_ = false; - integratedDependent_ = false; - antiDerivative_ = -1; - order_ = -1; - originalAntiDerivative_ = -1; - } - - /** - * Defines this variable as an integrated variable, also known - * as the independent variable of the DAE system (usually associated - * with time) - */ - inline void makeIntegratedVariable() { - integratedVariable_ = true; - integratedDependent_ = false; - antiDerivative_ = -1; - order_ = -1; - originalAntiDerivative_ = -1; - } - - /** - * Determines whether or not this is an integrated variable, also known - * as the independent variable of the DAE system (typically time). - * - * @return true if it is the integrated variable - */ - inline bool isIntegratedVariable() const { - return integratedVariable_; - } - - /** - * Returns the custom variable name. If the string is empty an - * automatically generated name will be used. - * - * @return the custom variable name - */ - inline const std::string& getName() const { - return name_; - } - - /** - * Defines a custom variable name. If the string is empty an - * automatically generated name will be used. - * - * @param name the custom variable name - */ - inline void setName(const std::string& name) { - name_ = name; - } - - /** - * Provides the variable index corresponding to the original model. - * - * @return The corresponding variable index in the original model. A - * negative value means that this variable was created by the - * algorithm. - */ - inline int getOriginalIndex() const { - return originalIndex_; - } - - /** - * Defines the variable index in the original model. - * - * @param originalIndex The corresponding variable index in the original - * model. A negative value means that this variable - * was created by the algorithm. - */ - inline void setOriginalIndex(int originalIndex) { - originalIndex_ = originalIndex; - } - - /** - * Provides the original variable index for which this variable is/was - * the time derivative (with the order provided by order_). - * A negative value means that the current variable was never a time - * derivative. - * A non-negative value does not mean that this variable should be - * treated as a time derivative since it might have been transformed - * into an algebraic variable by the algorithm. - * - * @return the index in the original model for which this variable is - * the time derivative - */ - inline int getOriginalAntiDerivative() const { - return originalAntiDerivative_; - } - - /** - * Defines the original variable index for which this variable is/was - * the time derivative (with the order provided by order_). - * A negative value means that the current variable was never a time - * derivative. - * A non-negative value does not mean that this variable should be - * treated as a time derivative since it might have been transformed - * into an algebraic variable by the algorithm. - * - * @param originalAntiDerivative the index in the original model for - * which this variable is the time - * derivative - */ - inline void setOriginalAntiDerivative(int originalAntiDerivative) { - originalAntiDerivative_ = originalAntiDerivative; - } - - /** - * Provides the order of a time derivative. - * A negative value means that it is a constant. - * An order higher than zero does not mean that the variable should be - * treated as a time derivative, it could very well be a time derivative - * transformed into an algebraic variable by the algorithm. - * - * @return The order of the time derivative - */ - inline int getOrder() const { - return order_; - } - - /** - * Defines the order of a time derivative. - * A negative value means that it is a constant. - * An order higher than zero does not mean that the variable should be - * treated as a time derivative, it could very well be a time derivative - * transformed into an algebraic variable by the algorithm. - * - * @param order The order of the time derivative - */ - inline void setOrder(int order) { - order_ = order; - } - - inline void printInfo(std::ostream& out = std::cout) const { - out << name_ << ":\n"; - if (antiDerivative_ >= 0) - out << " derivative-of: " << antiDerivative_ << "\n"; - if (derivative_ >= 0) - out << " derivative: " << derivative_ << "\n"; - if (integratedDependent_) - out << " integrated dependent\n"; - else if (integratedVariable_) - out << " integrated variable\n"; - out.flush(); - } - - inline virtual ~DaeVarInfo() { - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dummy_deriv.hpp b/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dummy_deriv.hpp deleted file mode 100644 index 2f513379d..000000000 --- a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dummy_deriv.hpp +++ /dev/null @@ -1,1554 +0,0 @@ -#ifndef CPPAD_CG_DUMMY_DERIV_INCLUDED -#define CPPAD_CG_DUMMY_DERIV_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ -#include -#include -#include -#include -#include - -#include -#include - -namespace CppAD { -namespace cg { - -/** - * Dummy derivatives DAE index reduction algorithm - */ -template -class DummyDerivatives : public DaeIndexReduction { - typedef CG CGBase; - typedef AD ADCG; - typedef Eigen::Matrix VectorB; - typedef Eigen::Matrix, Eigen::Dynamic, 1> VectorCB; - typedef Eigen::Matrix MatrixB; -protected: - /** - * Method used to identify the structural index - */ - DaeStructuralIndexReduction* const idxIdentify_; - /** - * typical values used to determine the Jacobian - */ - std::vector x_; - /** - * normalization constants for the variables (in the original order) - */ - std::vector normVar_; - /** - * normalization constants for the equations - */ - std::vector normEq_; - /** - * new index reduced model - */ - std::unique_ptr > reducedFun_; - /** - * Jacobian sparsity pattern of the reduced system - * (in the original variable order) - */ - std::vector jacSparsity_; - // the initial index of time derivatives - size_t diffVarStart_; - // the initial index of the differentiated equations - size_t diffEqStart_; - /** - * Normalized Jacobian of the index one system's differentiated - * equations relative to the time derivatives - * (in the new variable order). - */ - Eigen::SparseMatrix jacobian_; - /** - * Dummy derivatives - */ - std::vector*> dummyD_; - /** - * Attempt to reduce the total number of equations by performing variable - * substitutions - */ - bool reduceEquations_; - /** - * Attempt to generate a semi-explicit DAE by algebraic manipulations - */ - bool generateSemiExplicitDae_; - /** - * Reduce the total number of equations through variable substitutions - */ - bool reorder_; - /** - * - */ - bool avoidConvertAlg2DifVars_; -public: - - /** - * Creates the DAE index reduction algorithm that implements the dummy - * derivatives method. - * - * @param idxIdentify A structural index reduction method that identifies - * which variables and equations need to be - * differentiated - * @param x typical variable values (used to determine Jacobian values) - * @param normVar variable normalization values - * @param normEq equation normalization values - */ - DummyDerivatives(DaeStructuralIndexReduction& idxIdentify, - const std::vector& x, - const std::vector& normVar, - const std::vector& normEq) : - DaeIndexReduction(idxIdentify.getOriginalModel()), - idxIdentify_(&idxIdentify), - x_(x), - normVar_(normVar), - normEq_(normEq), - diffVarStart_(0), - diffEqStart_(idxIdentify.getOriginalModel().Range()), - reduceEquations_(true), - generateSemiExplicitDae_(false), - reorder_(true), - avoidConvertAlg2DifVars_(true) { - - for (Vnode* jj : idxIdentify.getGraph().variables()) { - if (jj->antiDerivative() != nullptr) { - diffVarStart_ = jj->index(); - break; - } - } - } - - inline bool isAvoidConvertAlg2DifVars() const { - return avoidConvertAlg2DifVars_; - } - - inline void setAvoidConvertAlg2DifVars(bool avoid) { - avoidConvertAlg2DifVars_ = avoid; - } - - /** - * Whether or not to attempt to generate a semi-explicit DAE by performing - * algebraic manipulations. - */ - inline bool isGenerateSemiExplicitDae() const { - return generateSemiExplicitDae_; - } - - /** - * Whether or not to attempt to generate a semi-explicit DAE by performing - * algebraic manipulations. - * Warning: The algebraic manipulations may fail to solve equations relative - * to the time derivatives. - */ - inline void setGenerateSemiExplicitDae(bool generateSemiExplicitDae) { - generateSemiExplicitDae_ = generateSemiExplicitDae; - } - - /** - * Whether or not the total number of equations is to be reduced by - * performing variable substitutions. - */ - inline bool isReduceEquations() const { - return reduceEquations_; - } - - /** - * Whether or not to attempt to reduce the total number of equations by - * performing variable substitutions. - */ - inline void setReduceEquations(bool reduceEquations) { - reduceEquations_ = reduceEquations; - } - - /** - * Whether or not variables and equations are to be reordered. - */ - inline bool isReorder() const { - return reorder_; - } - - /** - * Whether or not to reorder variables and equations. - * If reordering is enabled, variables will sorted as: - * {differential vars, algebraic vars, derivative var, integrated var}. - * Equations are sorted as: - * {differential equations, algebraic equations}. - */ - inline void setReorder(bool reorder) { - reorder_ = reorder; - } - - virtual inline std::unique_ptr>> reduceIndex(std::vector& newVarInfo, - std::vector& newEqInfo) override { - - /** - * Variable information for the reduced - */ - std::vector reducedVarInfo; - /** - * Equation information for the reduced model - */ - std::vector reducedEqInfo; - - reducedFun_ = idxIdentify_->reduceIndex(reducedVarInfo, reducedEqInfo); - if (reducedFun_.get() == nullptr) - return nullptr; //nothing to do (no index reduction required) - - if (this->verbosity_ >= Verbosity::Low) - log() << "######## Dummy derivatives method ########" << std::endl; - - newEqInfo = reducedEqInfo; // copy - addDummyDerivatives(reducedVarInfo, reducedEqInfo, newVarInfo); - - if (reduceEquations_ || generateSemiExplicitDae_) { - - matchVars2Eqs4Elimination(newVarInfo, newEqInfo); - - if (reduceEquations_) { - std::vector varInfo = newVarInfo; // copy - std::vector eqInfo = newEqInfo; // copy - std::unique_ptr > > funShort = reduceEquations(varInfo, newVarInfo, - eqInfo, newEqInfo); - reducedFun_.swap(funShort); - } - - if (generateSemiExplicitDae_) { - std::vector varInfo = newVarInfo; // copy - std::vector eqInfo = newEqInfo; // copy - std::unique_ptr > > semiExplicit = generateSemiExplicitDAE(*reducedFun_, - varInfo, newVarInfo, - eqInfo, newEqInfo); - reducedFun_.swap(semiExplicit); - } - } - - if (reorder_) { - std::vector varInfo = newVarInfo; // copy - std::vector eqInfo = newEqInfo; // copy - std::unique_ptr>> reorderedFun = reorderModelEqNVars(*reducedFun_, - varInfo, newVarInfo, - eqInfo, newEqInfo); - reducedFun_.swap(reorderedFun); - } - - return std::unique_ptr>>(reducedFun_.release()); - } - - inline virtual ~DummyDerivatives() { - } - -protected: - - using DaeIndexReduction::log; - - virtual inline void addDummyDerivatives(const std::vector& varInfo, - const std::vector& eqInfo, - std::vector& newVarInfo) { - auto& graph = idxIdentify_->getGraph(); - auto& vnodes = graph.variables(); - auto& enodes = graph.equations(); - - determineJacobian(); - - // variables of interest - std::vector*> vars; - vars.reserve(vnodes.size() - diffVarStart_); - typename std::vector*>::const_reverse_iterator rj; - for (rj = vnodes.rbegin(); rj != vnodes.rend(); ++rj) { - Vnode* jj = *rj; - if (jj->antiDerivative() != nullptr && jj->derivative() == nullptr) { - vars.push_back(jj); // highest order time derivatives in the index 1 model - } - } - - // should be already fairly sorted, but sort anyway - std::sort(vars.begin(), vars.end(), sortVnodesByOrder); - - // equations of interest - typename std::vector*>::const_reverse_iterator ri; - std::vector*> eqs; - eqs.reserve(enodes.size() - diffEqStart_); - for (ri = enodes.rbegin(); ri != enodes.rend(); ++ri) { - Enode* ii = *ri; - if (ii->derivativeOf() != nullptr && ii->derivative() == nullptr) { - eqs.push_back(ii); - } - } - - - MatrixB workJac; - - while (true) { - - if (this->verbosity_ >= Verbosity::High) { - log() << "# equation selection: "; - for (size_t i = 0; i < eqs.size(); i++) - log() << *eqs[i] << "; "; - log() << "\n"; - - log() << "# variable selection: "; - for (size_t j = 0; j < vars.size(); j++) - log() << *vars[j] << "; "; - log() << "\n"; - } - - // Exploit the current equations for elimination of candidates - selectDummyDerivatives(eqs, vars, workJac); - - /** - * Consider all of the current equations that are - * differentiated versions of the original ones. - * Collect their predecessors and let them be the - * current equations. - */ - std::vector*> newEqs; - newEqs.reserve(eqs.size()); - - for (Enode* i : eqs) { - Enode* ii = i->derivativeOf(); - if (ii != nullptr && ii->derivativeOf() != nullptr) { - newEqs.push_back(ii); - } - } - eqs.swap(newEqs); - - if (eqs.empty()) { - break; - } - - /** - * Consider all current unknowns that are at least of - * order one. Collect their predecessors of one order - * less and let them be the current candidates for - * elimination. - */ - std::vector*> varsNew; - varsNew.reserve(vars.size()); - for (Vnode* j : vars) { - Vnode* v = j->antiDerivative(); - if (v != nullptr && v->antiDerivative() != nullptr) { - varsNew.push_back(v); - } - } - vars.swap(varsNew); - } - - - /** - * Prepare the output information - */ - newVarInfo = varInfo; //copy - for (Vnode* j : dummyD_) { - CPPADCG_ASSERT_UNKNOWN(j->tapeIndex() >= 0); - CPPADCG_ASSERT_UNKNOWN(j->antiDerivative() != nullptr); - CPPADCG_ASSERT_UNKNOWN(j->antiDerivative()->tapeIndex() >= 0); - - newVarInfo[j->tapeIndex()].setAntiDerivative(-1); - newVarInfo[j->antiDerivative()->tapeIndex()].setDerivative(-1); - } - - if (this->verbosity_ >= Verbosity::Low) { - log() << "## dummy derivatives:\n"; - - for (Vnode* j : dummyD_) - log() << "# " << *j << " \t" << newVarInfo[j->tapeIndex()].getName() << "\n"; - log() << "# \n"; - if (this->verbosity_ >= Verbosity::High) { - graph.printModel(log(), *reducedFun_, newVarInfo, eqInfo); - } - } - - } - - /** - * Attempts to reduce the number of equations by variable substitution. - * - * @param newVarInfo Variable information of the resulting model - * @return The new DAE reduced model with (possibly) less equations and - * variables - */ - inline std::unique_ptr > reduceEquations(const std::vector& reducedVarInfo, - std::vector& newVarInfo, - const std::vector& reducedEqInfo, - std::vector& newEqInfo) { - using namespace std; - using std::vector; - using std::map; - using std::map; - - auto& graph = idxIdentify_->getGraph(); - //auto& vnodes = graph.variables(); - auto& enodes = graph.equations(); - - CPPADCG_ASSERT_UNKNOWN(reducedVarInfo.size() == reducedFun_->Domain()); - CPPADCG_ASSERT_UNKNOWN(reducedEqInfo.size() == reducedFun_->Range()); - - newEqInfo = reducedEqInfo; // copy - - /** - * Generate an operation graph - */ - CodeHandler handler; - - vector indep0(reducedFun_->Domain()); - handler.makeVariables(indep0); - - vector res0 = graph.forward0(*reducedFun_, indep0); - - map assignedVar2Eq; - for (size_t i = 0; i < newEqInfo.size(); ++i) { - DaeEquationInfo& newEq = newEqInfo[i]; - if (newEq.getAssignedVarIndex() >= 0) - assignedVar2Eq[newEq.getAssignedVarIndex()] = i; - } - - /** - * maps the equations indexes of the reduced model to the new - * equation indexes in the model with less equations and variables - * (removed equations have negative indexes) - */ - vector eqIndexReduced2Short(enodes.size()); - for (size_t i = 0; i < eqIndexReduced2Short.size(); i++) { - eqIndexReduced2Short[i] = i; - } - - /** - * maps the variables indexes in the tape of the reduced model to - * the new tape indexes in the model with less equations and - * variables (removed variables have negative indexes) - */ - vector tapeIndexReduced2Short(reducedVarInfo.size()); - for (size_t j = 0; j < tapeIndexReduced2Short.size(); j++) { - tapeIndexReduced2Short[j] = j; - } - - /** - * attempt to eliminate dummy derivatives and the equation they are - * assigned to - */ - set erasedVariables; - set erasedEquations; - - if (this->verbosity_ >= Verbosity::High) - log() << "Reducing total number of equations by symbolic manipulation:" << std::endl; - - for (Vnode* dummy : dummyD_) { - - /** - * Determine which equation to use to eliminate the dummy derivative - */ - map::const_iterator ita = assignedVar2Eq.find(dummy->tapeIndex()); - if (ita == assignedVar2Eq.end()) { - if (this->verbosity_ >= Verbosity::High) - log() << "unable to solve for variable " << dummy->name() << "." << std::endl; - - continue; // unable to solve for a dummy variable: keep the equation and variable - } - int bestEquation = ita->second; - - try { - // eliminate all references to the dummy variable by substitution - handler.substituteIndependent(indep0[dummy->tapeIndex()], res0[bestEquation]); - tapeIndexReduced2Short[dummy->tapeIndex()] = -1; - eqIndexReduced2Short[bestEquation] = -1; - - if (this->verbosity_ >= Verbosity::High) { - log() << "######### use equation " << *enodes[newEqInfo[bestEquation].getId()] << " to solve for variable " << dummy->name() << std::endl; - erasedVariables.insert(dummy->tapeIndex()); - erasedEquations.insert(bestEquation); - printModel(log(), handler, res0, reducedVarInfo, erasedVariables, erasedEquations); - } - - } catch (const CGException& ex) { - // unable to solve for a dummy variable: keep the equation and variable - if (this->verbosity_ >= Verbosity::High) - log() << "unable to use equation " << *enodes[newEqInfo[bestEquation].getId()] << " to solve for variable " << dummy->name() << ": " << ex.what() << std::endl; - } - } - - // determine the new equation indexes - for (size_t i = 0; i < eqIndexReduced2Short.size(); i++) { - if (eqIndexReduced2Short[i] < 0) { // removed equation - for (size_t ii = i + 1; ii < eqIndexReduced2Short.size(); ii++) { - if (eqIndexReduced2Short[ii] >= 0) { - eqIndexReduced2Short[ii]--; - } - } - } - } - - // determine the new indexes in the tape - for (size_t p = 0; p < tapeIndexReduced2Short.size(); p++) { - if (tapeIndexReduced2Short[p] < 0) { - // removed from model - for (size_t p2 = p + 1; p2 < tapeIndexReduced2Short.size(); p2++) { - if (tapeIndexReduced2Short[p2] >= 0) { - tapeIndexReduced2Short[p2]--; - } - } - } - } - - /** - * Prepare the output information - */ - CPPADCG_ASSERT_UNKNOWN(tapeIndexReduced2Short.size() == reducedVarInfo.size()); - - newVarInfo = reducedVarInfo; // copy - for (int p = tapeIndexReduced2Short.size() - 1; p >= 0; p--) { - if (tapeIndexReduced2Short[p] < 0) { // removed from model - newVarInfo.erase(newVarInfo.begin() + p); - for (size_t pp = 0; pp < tapeIndexReduced2Short.size(); pp++) { - DaeVarInfo& v = newVarInfo[pp]; - if (v.getAntiDerivative() > p) { - v.setAntiDerivative(v.getAntiDerivative() - 1); - } else if (v.getAntiDerivative() == p) { - v.setAntiDerivative(-1); - } - if (v.getDerivative() > p) { - v.setDerivative(v.getDerivative() - 1); - } else if (v.getDerivative() == p) { - v.setDerivative(-1); - } - } - } - } - - for (int p = eqIndexReduced2Short.size() - 1; p >= 0; p--) { - if (eqIndexReduced2Short[p] < 0) {// removed from model - newEqInfo.erase(newEqInfo.begin() + p); - } else { - DaeEquationInfo& eq = newEqInfo[p]; - int reducedVIndex = eq.getAssignedVarIndex(); - if (reducedVIndex >= 0) - eq.setAssignedVarIndex(tapeIndexReduced2Short[reducedVIndex]); - if (eq.getAntiDerivative() >= 0) - eq.setAntiDerivative(eqIndexReduced2Short[eq.getAntiDerivative()]); - } - } - - /** - * Implement the model after after the reduction of equations and - * variables by substitution - */ - std::unique_ptr > shortFun(generateReorderedModel(handler, res0, - reducedVarInfo, newVarInfo, - reducedEqInfo, newEqInfo)); - - if (this->verbosity_ >= Verbosity::High) { - log() << "DAE with less equations and variables:\n"; - graph.printModel(log(), *shortFun, newVarInfo, newEqInfo); - } - - return shortFun; - } - - /** - * Attempts to generate a semi-explicit DAE. - * - * @param reorder place all the differential equations and variables - * together - * @param differentialEqs - * @return The new semi-explicit DAE model with less variables (without - * the time derivative variables) - * @throws CGException on failure - */ - inline std::unique_ptr > generateSemiExplicitDAE(ADFun >& fun, - const std::vector& varInfo, - std::vector& newVarInfo, - const std::vector& eqInfo, - std::vector& newEqInfo) { - using namespace std; - using std::vector; - using std::map; - - auto& graph = idxIdentify_->getGraph(); - - newEqInfo = eqInfo; // copy (we will have the same number of equations) - - /** - * Generate an operation graph - */ - CodeHandler handler; - - vector indep0(fun.Domain()); - handler.makeVariables(indep0); - - vector res0 = graph.forward0(fun, indep0); - - map assignedVar2Eq; - for (size_t i = 0; i < newEqInfo.size(); ++i) { - DaeEquationInfo& newEq = newEqInfo[i]; - assignedVar2Eq[newEq.getAssignedVarIndex()] = i; - } - - /** - * Eliminate time derivatives from equations - */ - for (size_t j = 0; j < varInfo.size(); ++j) { - const DaeVarInfo& jj = varInfo[j]; - if (jj.getAntiDerivative() < 0) { - continue; // not a time derivative - } - CGBase& indep = indep0[j]; // the time derivative - /** - * Determine which equation to keep as differential - */ - map::const_iterator ita = assignedVar2Eq.find(j); - if (ita == assignedVar2Eq.end()) { - throw CGException("Failed to generate semi-explicit DAE: unable to create an explicit equation for ", jj.getName()); - } - - int bestEquation = ita->second; - - try { - CGBase& dep = res0[bestEquation]; // the equation residual - - handler.substituteIndependent(indep, dep); // removes indep from the list of variables - - OperationNode* alias = indep.getOperationNode(); - CPPADCG_ASSERT_UNKNOWN(alias != nullptr && alias->getOperationType() == CGOpCode::Alias); - dep.getOperationNode()->makeAlias(alias->getArguments()[0]); // not a residual anymore but equal to alias (explicit equation) - - // it is now an explicit differential equation - newEqInfo[bestEquation].setExplicit(true); - // the derivative variable will disappear, associate the equation with the original variable - newEqInfo[bestEquation].setAssignedVarIndex(jj.getAntiDerivative()); - } catch (const CGException& ex) { - // unable to solve for a dummy variable: keep the equation and variable - throw CGException("Failed to generate semi-explicit DAE: ", ex.what()); - } - } - - /** - * determine the variable indexes after the elimination of the time - * derivatives - */ - vector varIndexOld2New(varInfo.size(), -1); - size_t count = 0; - for (size_t j = 0; j != varInfo.size(); ++j) { - // exclude derivatives (they will be removed) - if (varInfo[j].getAntiDerivative() < 0) { - varIndexOld2New[j] = count++; - } - } - - for (size_t i = 0; i < newEqInfo.size(); ++i) { - const DaeEquationInfo& ii = newEqInfo[i]; - int j = ii.getAssignedVarIndex(); - if (j >= 0) - newEqInfo[i].setAssignedVarIndex(varIndexOld2New[j]); - } - - /** - * Prepare the output information - */ - newVarInfo = varInfo; - for (int j = newVarInfo.size() - 1; j >= 0; --j) { - if (newVarInfo[j].getAntiDerivative() >= 0) { - // a derivative - newVarInfo.erase(newVarInfo.begin() + j); - } - } - for (size_t j = 0; j < newVarInfo.size(); j++) { - newVarInfo[j].setDerivative(-1); // no derivatives in tape - } - - /** - * Implement the reordering and derivative variable elimination in - * the model - */ - std::unique_ptr > semiExplicitFun(generateReorderedModel(handler, res0, varInfo, newVarInfo, eqInfo, newEqInfo)); - - if (this->verbosity_ >= Verbosity::High) { - log() << "Semi-Eplicit DAE:\n"; - graph.printModel(log(), *semiExplicitFun, newVarInfo, newEqInfo); - } - - return semiExplicitFun; - } - - inline void matchVars2Eqs4Elimination(std::vector& varInfo, - std::vector& eqInfo) { - using std::vector; - using std::map; - - auto& graph = idxIdentify_->getGraph(); - auto& vnodes = graph.variables(); - auto& enodes = graph.equations(); - - CPPADCG_ASSERT_UNKNOWN(eqInfo.size() == enodes.size()); - CPPADCG_ASSERT_UNKNOWN(varInfo.size() == reducedFun_->Domain()); - CPPADCG_ASSERT_UNKNOWN(eqInfo.size() == reducedFun_->Range()); - - CodeHandler handler; - - vector indep0(reducedFun_->Domain()); - handler.makeVariables(indep0); - - vector res0 = graph.forward0(*reducedFun_, indep0); - - vector jacSparsity = jacobianSparsity >(*reducedFun_); - - vector*> diffVariables; - vector*> dummyVariables; - vector*> variables; - vector*> equations(enodes.size(), nullptr); - try { - /** - * Create a new bipartite graph - */ - // create variable nodes - map*, Vnode*> eliminateOrig2New; - for (size_t j = 0; j < vnodes.size(); j++) { - Vnode* v = vnodes[j]; - if (std::find(dummyD_.begin(), dummyD_.end(), v) != dummyD_.end()) { - if (reduceEquations_) { - dummyVariables.push_back(new Vnode(j, v->tapeIndex(), v->name())); - eliminateOrig2New[v] = dummyVariables.back(); - } - } else if (v->antiDerivative() != nullptr) { - if (generateSemiExplicitDae_) { - diffVariables.push_back(new Vnode(j, v->tapeIndex(), v->name())); - eliminateOrig2New[v] = diffVariables.back(); - } - } - } - - variables.reserve(diffVariables.size() + dummyVariables.size()); - variables.insert(variables.end(), diffVariables.begin(), diffVariables.end()); // must be added 1st (priority) - variables.insert(variables.end(), dummyVariables.begin(), dummyVariables.end()); - - // create equation nodes - for (size_t i = 0; i < enodes.size(); i++) { - equations[i] = new Enode(i, enodes[i]->name()); - const vector*>& origVars = enodes[i]->originalVariables(); - for (size_t p = 0; p < origVars.size(); p++) { - Vnode* jOrig = origVars[p]; - - typename map*, Vnode*>::const_iterator it; - it = eliminateOrig2New.find(jOrig); - if (it != eliminateOrig2New.end() && - jacSparsity[varInfo.size() * i + jOrig->tapeIndex()]) { - Vnode* j = it->second; - - CGBase& dep = res0[i]; // the equation residual - CGBase& indep = indep0[j->tapeIndex()]; - - if (handler.isSolvable(*dep.getOperationNode(), *indep.getOperationNode())) { - equations[i]->addVariable(j); - } - } - } - } - - map*> tape2FreeVariables; - for (Vnode* j : variables) { - tape2FreeVariables[j->tapeIndex()] = j; - } - - - /** - * Match equations to variables (derivatives and dummy derivatives only) - */ - while (true) { - size_t assigned; - do { - do { - /** - * assign variables that can only be solved by a single equation - */ - do { - assigned = 0; - for (Vnode* j : diffVariables) { - if (!j->isDeleted() && j->equations().size() == 1) { - Enode& i = *j->equations()[0]; - if (i.assignmentVariable() == nullptr) { - if (!assignVar2Equation(i, res0, *j, indep0, handler, - jacSparsity, tape2FreeVariables, - equations, varInfo)) { - throw CGException("Failed to solve equation ", i.name(), " for variable ", j->name()); - } - assigned++; - } - } - } - } while (assigned > 0); - - /** - * assign dummy derivatives that can only be solved by a single - * equation - */ - assigned = 0; - for (Vnode* j : dummyVariables) { - if (!j->isDeleted() && j->equations().size() == 1) { - Enode& i = *j->equations()[0]; - if (i.assignmentVariable() == nullptr) { - if (assignVar2Equation(i, res0, *j, indep0, handler, - jacSparsity, tape2FreeVariables, - equations, varInfo)) - assigned++; - } - } - } - } while (assigned > 0); - - /** - * assign equations that can only be used to solve for - * a single variable - */ - assigned = 0; - for (Enode* i : equations) { - if (i->assignmentVariable() == nullptr && i->variables().size() == 1) { - Vnode* j = i->variables()[0]; - if (assignVar2Equation(*i, res0, *j, indep0, handler, - jacSparsity, tape2FreeVariables, - equations, varInfo)) - assigned++; - } - } - - } while (assigned > 0); - - /** - * All variables have at least two equations that can be used - * and all equations have at least two variables - * choose a tearing variable/equation - */ - assigned = 0; - for (Vnode* j : variables) { - if (!j->isDeleted()) { - for (Enode* i : j->equations()) { - if (i->assignmentVariable() == nullptr) { - if (assignVar2Equation(*i, res0, *j, indep0, handler, - jacSparsity, tape2FreeVariables, - equations, varInfo)) { - assigned++; - break; - } - } - } - if (assigned > 0) - break; - } - } - - if (assigned == 0) { - break; // done - } - } - - - /** - * Assign algebraic variables (except dummy derivatives) - * This is only for information purposes! - */ - for (Vnode* j : variables) { // previous assignments must not change! - if (j->assignmentEquation() != nullptr) { - j->deleteNode(); - } - } - - AugmentPathDepthLookahead augment; - for(Enode* i: equations) { - if (i->assignmentVariable() == nullptr) { - augment.augmentPath(*i); - } - } - - /** - * save results - */ - for (Vnode* j : variables) { - if (j->assignmentEquation() != nullptr) { - int i = j->assignmentEquation()->index(); - DaeEquationInfo& eq = eqInfo[i]; - - if (eq.getAssignedVarIndex() != int(j->tapeIndex())) { - eq.setAssignedVarIndex(j->tapeIndex()); - } - } - } - - // verify results - if (generateSemiExplicitDae_) { - std::string error; - for (Vnode* j : diffVariables) { - if (j->assignmentEquation() == nullptr) { - // failed!!! - if (!error.empty()) - error += ","; - error += " " + j->name(); - } - } - if (!error.empty()) - throw CGException("Failed to generate semi-explicit DAE. Could not solve system for the following variables:", error); - } - - } catch (...) { - deleteVectorValues(diffVariables); - deleteVectorValues(dummyVariables); - deleteVectorValues(equations); - throw; - } - - if (this->verbosity_ >= Verbosity::High) { - for (Vnode* j : variables) { - if (j->assignmentEquation() != nullptr) - log() << "## Variable " + j->name() << " assigned to equation " << j->assignmentEquation()->name() << "\n"; - } - log() << std::endl; - } - deleteVectorValues(diffVariables); - deleteVectorValues(dummyVariables); - deleteVectorValues(equations); - } - - inline bool assignVar2Equation(Enode& i, std::vector& res0, - Vnode& j, std::vector& indep0, - CodeHandler& handler, - std::vector& jacSparsity, - const std::map*>& tape2FreeVariables, - std::vector*>& equations, - std::vector& varInfo) { - using namespace std; - using std::vector; - using std::map; - - std::vector localJacSparsity = jacSparsity; - const size_t n = varInfo.size(); - - /** - * Implement the assignment in the model - */ - CGBase& dep = res0[i.index()]; - CGBase& indep = indep0[j.tapeIndex()]; - - std::string indepName; - if (indep.getOperationNode()->getName() != nullptr) { - indepName = *indep.getOperationNode()->getName(); - } - - - try { - handler.substituteIndependent(indep, dep, false); // indep not removed from the list of variables yet - - OperationNode* alias = indep.getOperationNode(); - CPPADCG_ASSERT_UNKNOWN(alias != nullptr && alias->getOperationType() == CGOpCode::Alias); - - // it is now an explicit differential equation - //newEqInfo[bestEquation].setExplicit(true); - // the derivative variable will disappear, associate the equation with the original variable - //newEqInfo[bestEquation].setAssignedVarIndex(jj.getAntiDerivative()); - } catch (const CGException& ex) { - // unable to solve for a dummy variable: keep the equation and variable - throw CGException("Failed to solve equation ", i.name(), " for variable ", j.name(), ": ", ex.what()); - } - - - /** - * Update the connections to the other equations affected by the - * substitution - */ - vector nnzs; - for (const auto& it : tape2FreeVariables) { - size_t tapeJ = it.first; - if (localJacSparsity[n * i.index() + tapeJ] && tapeJ != j.tapeIndex()) { - nnzs.push_back(tapeJ); - } - } - set*> affected; - for (size_t e = 0; e < equations.size(); ++e) { - if (equations[e] != &i && localJacSparsity[n * e + j.tapeIndex()]) { - localJacSparsity[n * e + j.tapeIndex()] = false; // eliminated by substitution - affected.insert(equations[e]); - for (size_t p = 0; p < nnzs.size(); ++p) { - localJacSparsity[n * e + nnzs[p]] = true; - } - } - } - - if (affected.size() > 0) { - /** - * Redetermine solvability for the affected equations - */ - map*> > solvable; - for (size_t e = 0; e < equations.size(); ++e) { - Enode* eq = equations[e]; - if (&i != eq && affected.find(eq) == affected.end()) { - // no change - for (size_t v = 0; v < eq->variables().size(); ++v) { - solvable[eq->variables()[v]->tapeIndex()].insert(eq); - } - } - } - - // redetermine solvability - for (Enode* itAff : affected) { - Enode& a = *itAff; - for (const auto& it : tape2FreeVariables) { - size_t jj = it.first; - if (localJacSparsity[n * a.index() + jj]) { - if (handler.isSolvable(*res0[a.index()].getOperationNode(), *indep0[jj].getOperationNode())) { - solvable[jj].insert(&a); - } - } - } - } - - // check if any variable stops being solvable - bool ok = true; - for (const auto& it : tape2FreeVariables) { - Vnode* v = it.second; - if (v == &j) - continue; - - if (v->assignmentEquation() != nullptr) { - if (affected.count(v->assignmentEquation()) > 0 && - solvable[v->tapeIndex()].count(v->assignmentEquation()) == 0) { - ok = false; - break; - } - } else if (solvable[v->tapeIndex()].size() == 0) { - ok = false; - break; - } - } - - if (!ok) { - handler.undoSubstituteIndependent(*indep.getOperationNode()); - if (indepName.size() > 0) { - indep.getOperationNode()->setName(indepName); - } - return false; - } - - /** - * Implement changes in graph - */ - for (Enode* itAff : affected) { - Enode& a = *itAff; - for (const auto& it : tape2FreeVariables) { - size_t v = it.first; - if (localJacSparsity[n * a.index() + v]) { - if (solvable[v].count(&a) > 0) { - a.addVariable(it.second); - } else { - // not solvable anymore - a.deleteNode(it.second); - } - } - } - } - - } - - /** - * Finalize model - */ - handler.removeIndependent(*indep.getOperationNode()); - - /** - * Implement the assignment in the graph - */ - j.setAssignmentEquation(i, log(), this->verbosity_); - j.deleteNode(log(), this->verbosity_); - - jacSparsity = localJacSparsity; - - return true; - } - - inline std::unique_ptr > reorderModelEqNVars(ADFun >& fun, - const std::vector& varInfo, - std::vector& newVarInfo, - const std::vector& eqInfo, - std::vector& newEqInfo) { - - using namespace std; - using std::vector; - - auto& graph = idxIdentify_->getGraph(); - - /** - * Determine the variables that have derivatives in the model - */ - std::set oldVarWithDerivatives; // indexes of old variables (before reordering) with derivatives - for (size_t i = 0; i < eqInfo.size(); i++) { - if (eqInfo[i].isExplicit() && eqInfo[i].getAssignedVarIndex() >= 0) { - oldVarWithDerivatives.insert(eqInfo[i].getAssignedVarIndex()); - } - } - - if (oldVarWithDerivatives.empty()) { - // no semi-explicit model generated - for (size_t j = 0; j < varInfo.size(); j++) { - int index = j; - bool differential = false; - while (varInfo[index].getAntiDerivative() >= 0) { - index = varInfo[index].getAntiDerivative(); - differential = true; - } - - if (differential) { - oldVarWithDerivatives.insert(index); - } - } - } - - /** - * sort variables - */ - std::vector varOrder(varInfo.size()); - for (size_t j = 0; j < varInfo.size(); j++) { - size_t j0; - int derivOrder = graph.determineVariableDiffOrder(varInfo, j, j0); - if (varInfo[j].isIntegratedVariable()) { - derivOrder = -2; // so that it goes last - } - bool hasDerivatives = oldVarWithDerivatives.find(j) != oldVarWithDerivatives.end(); - varOrder[j] = DaeVarOrderInfo(j, j0, hasDerivatives, derivOrder); - } - - std::sort(varOrder.begin(), varOrder.end(), sortVariablesByOrder); - - /** - * reorder variables - */ - std::vector varIndexOld2New(varInfo.size(), -1); - for (size_t j = 0; j < varOrder.size(); ++j) { - varIndexOld2New[varOrder[j].originalIndex] = j; - } - - newVarInfo.resize(varInfo.size()); - for (size_t j = 0; j < varOrder.size(); ++j) { - newVarInfo[j] = varInfo[varOrder[j].originalIndex]; - int oldDerivOfIndex = newVarInfo[j].getAntiDerivative(); - if (oldDerivOfIndex >= 0) - newVarInfo[j].setAntiDerivative(varIndexOld2New[oldDerivOfIndex]); - int oldDerivIndex = newVarInfo[j].getDerivative(); - if (oldDerivIndex >= 0) - newVarInfo[j].setDerivative(varIndexOld2New[oldDerivIndex]); - } - - /** - * reorder equations - */ - newEqInfo = eqInfo; //copy - for (size_t i = 0; i < newEqInfo.size(); i++) { - int oldVIndex = newEqInfo[i].getAssignedVarIndex(); - if (oldVIndex >= 0) { - newEqInfo[i].setAssignedVarIndex(varIndexOld2New[oldVIndex]); - } - } - - std::vector eqOrder(newEqInfo.size()); - for (size_t i = 0; i < newEqInfo.size(); i++) { - int assignedVar = newEqInfo[i].getAssignedVarIndex(); - size_t i0 = i; - while (newEqInfo[i0].getAntiDerivative() >= 0) { - i0 = newEqInfo[i0].getAntiDerivative(); - } - bool isDifferential = newEqInfo[i].isExplicit() || (assignedVar >= 0 && newVarInfo[assignedVar].getAntiDerivative() >= 0); - eqOrder[i] = DaeEqOrderInfo(i, i0, isDifferential, assignedVar); - } - - std::sort(eqOrder.begin(), eqOrder.end(), sortEquationByAssignedOrder2); - - std::vector newEqInfo2(newEqInfo.size()); - for (size_t i = 0; i < eqOrder.size(); i++) { - newEqInfo2[i] = newEqInfo[eqOrder[i].originalIndex]; - } - newEqInfo = newEqInfo2; - - - /** - * Generate an operation graph - */ - CodeHandler handler; - - vector indep0(fun.Domain()); - handler.makeVariables(indep0); - - const vector res0 = graph.forward0(fun, indep0); - - /** - * Implement the reordering in the model - */ - std::unique_ptr > reorderedFun(generateReorderedModel(handler, res0, varInfo, newVarInfo, eqInfo, newEqInfo)); - - if (this->verbosity_ >= Verbosity::High) { - log() << "reordered DAE equations and variables:\n"; - graph.printModel(log(), *reorderedFun, newVarInfo, newEqInfo); - } - - return reorderedFun; - } - - inline ADFun* generateReorderedModel(CodeHandler& handler, - const std::vector& res0, - const std::vector& varInfo, - const std::vector& newVarInfo, - const std::vector& eqInfo, - const std::vector& newEqInfo) const { - using std::vector; - - vector indepNewOrder(handler.getIndependentVariableSize()); - CPPADCG_ASSERT_UNKNOWN(indepNewOrder.size() == newVarInfo.size()); - - for (size_t p = 0; p < newVarInfo.size(); p++) { - int origIndex = newVarInfo[p].getOriginalIndex(); - if (origIndex >= 0) { - indepNewOrder[p] = x_[origIndex]; - } - } - - Independent(indepNewOrder); - - /** - * the model must be called with the handler order - * - * removed variables using substitution are taken out from the list - * of independent variables in the handler - */ - std::set newIds; - for (size_t j = 0; j < newVarInfo.size(); j++) { - newIds.insert(newVarInfo[j].getId()); - } - - std::map varId2HandlerIndex; - size_t handlerIndex = 0; // start the variable count again since some variable might have been removed - for (size_t j = 0; j < varInfo.size(); j++) { - int id = varInfo[j].getId(); - if (newIds.find(id) != newIds.end()) { - varId2HandlerIndex[id] = handlerIndex++; // not removed from model - } - } - - vector indepHandlerOrder(handler.getIndependentVariableSize()); - for (size_t p = 0; p < newVarInfo.size(); p++) { - size_t id = newVarInfo[p].getId(); - indepHandlerOrder[varId2HandlerIndex[id]] = indepNewOrder[p]; - } - - // reorder equations - std::map eqId2OldIndex; - for (size_t i = 0; i < eqInfo.size(); i++) { - eqId2OldIndex[eqInfo[i].getId()] = i; - } - - vector resNewOrder(newEqInfo.size()); - for (size_t i = 0; i < newEqInfo.size(); i++) { - size_t oldIndex = eqId2OldIndex[newEqInfo[i].getId()]; - resNewOrder[i] = res0[oldIndex]; - } - - // evaluate the model - Evaluator evaluator0(handler); - evaluator0.setPrintFor(idxIdentify_->getGraph().isPreserveNames()); // variable names saved with CppAD::PrintFor - vector depNewOrder = evaluator0.evaluate(indepHandlerOrder, resNewOrder); - - return new ADFun(indepNewOrder, depNewOrder); - } - - /** - * Determines the Jacobian relative to the differential variables - * (e.g. dxdt) - */ - inline void determineJacobian() { - using namespace std; - using std::vector; - - const size_t n = reducedFun_->Domain(); - const size_t m = reducedFun_->Range(); - - auto& graph = idxIdentify_->getGraph(); - auto& vnodes = graph.variables(); - auto& enodes = graph.equations(); - - jacSparsity_ = jacobianReverseSparsity, CGBase>(*reducedFun_); // in the original variable order - - vector row, col; - row.reserve((vnodes.size() - diffVarStart_) * (m - diffEqStart_)); - col.reserve(row.capacity()); - - for (size_t i = diffEqStart_; i < m; i++) { - for (size_t j = diffVarStart_; j < vnodes.size(); j++) { - CPPADCG_ASSERT_UNKNOWN(vnodes[j]->antiDerivative() != nullptr); - size_t t = vnodes[j]->tapeIndex(); - if (jacSparsity_[i * n + t]) { - row.push_back(i); - col.push_back(t); - } - } - } - - vector > jac(row.size()); - - vector > indep(n); - std::copy(x_.begin(), x_.end(), indep.begin()); - std::fill(indep.begin() + x_.size(), indep.end(), 0); - - CppAD::sparse_jacobian_work work; // temporary structure for CPPAD - reducedFun_->SparseJacobianReverse(indep, jacSparsity_, - row, col, jac, work); - - // resize and zero matrix - jacobian_.resize(m - diffEqStart_, vnodes.size() - diffVarStart_); - - map*> origIndex2var; - for (size_t j = diffVarStart_; j< vnodes.size(); j++) { - Vnode* jj = vnodes[j]; - origIndex2var[jj->tapeIndex()] = jj; - } - - // normalize values - for (size_t e = 0; e < jac.size(); e++) { - Enode* eqOrig = enodes[row[e]]->originalEquation(); - Vnode* vOrig = origIndex2var[col[e]]->originalVariable(graph.getOrigTimeDependentCount()); - - // normalized jacobian value - Base normVal = jac[e].getValue() * normVar_[vOrig->tapeIndex()] - / normEq_[eqOrig->index()]; - - size_t i = row[e]; // same order - size_t j = origIndex2var[col[e]]->index(); // different order than in model/tape - - jacobian_.coeffRef(i - diffEqStart_, j - diffVarStart_) = normVal; - } - - jacobian_.makeCompressed(); - - if (this->verbosity_ >= Verbosity::High) { - log() << "\npartial jacobian:\n" << jacobian_ << "\n\n"; - //cout << jacobian_.triangularView () << "\n\n"; - } - } - - inline void selectDummyDerivatives(const std::vector* >& eqs, - const std::vector* >& vars, - MatrixB& work) { - - if (eqs.size() == vars.size()) { - dummyD_.insert(dummyD_.end(), vars.begin(), vars.end()); - if (this->verbosity_ >= Verbosity::High) { - log() << "# new dummy derivatives: "; - for (size_t j = 0; j < vars.size(); j++) - log() << *vars[j] << "; "; - log() << " \n"; - } -#ifndef NDEBUG - for (Vnode* it : vars) { - CPPADCG_ASSERT_UNKNOWN(std::find(dummyD_.begin(), dummyD_.end(), it) == dummyD_.end()); - } -#endif - return; - } - - /** - * Determine the columns that must be removed - */ - std::set excludeCols; - for (size_t j = 0; j < vars.size(); j++) { - Vnode* jj = vars[j]; - bool notZero = false; - for (size_t i = 0; i < eqs.size(); i++) { - Enode* ii = eqs[i]; - Base val = jacobian_.coeff(ii->index() - diffEqStart_, jj->index() - diffVarStart_); - if (val != Base(0.0)) { - notZero = true; - break; - } - } - if (!notZero) { - // all zeros: must not choose this column/variable - excludeCols.insert(j); - } - } - - std::vector* > varsLocal; - varsLocal.reserve(vars.size() - excludeCols.size()); - for (size_t j = 0; j < vars.size(); j++) { - if (excludeCols.find(j) == excludeCols.end()) { - varsLocal.push_back(vars[j]); - } - } - - - work.setZero(eqs.size(), varsLocal.size()); - - // determine the rows that only contain a single nonzero (a single column) - for (size_t i = 0; i < eqs.size(); i++) { - Enode* ii = eqs[i]; - for (size_t j = 0; j < varsLocal.size(); j++) { - Vnode* jj = varsLocal[j]; - Base val = jacobian_.coeff(ii->index() - diffEqStart_, jj->index() - diffVarStart_); - if (val != Base(0.0)) { - work(i, j) = val; - } - } - } - - if (this->verbosity_ >= Verbosity::High) - log() << "subset Jac:\n" << work << "\n"; - - Eigen::ColPivHouseholderQR qr(work); - qr.compute(work); - - if(qr.info() != Eigen::Success) { - throw CGException("Failed to select dummy derivatives! " - "QR decomposition of a submatrix of the Jacobian failed!"); - } else if (qr.rank() < work.rows()) { - throw CGException("Failed to select dummy derivatives! " - "The resulting system is probably singular for the provided data."); - } - - typedef typename Eigen::ColPivHouseholderQR::PermutationType PermutationMatrix; - typedef typename PermutationMatrix::IndicesType Indices; - - const PermutationMatrix& p = qr.colsPermutation(); - const Indices& indices = p.indices(); - - if (this->verbosity_ >= Verbosity::High) { - log() << "## matrix Q:\n"; - MatrixB q = qr.matrixQ(); - log() << q << "\n"; - log() << "## matrix R:\n"; - MatrixB r = qr.matrixR().template triangularView(); - log() << r << "\n"; - log() << "## matrix P: " << indices.transpose() << "\n"; - } - - if (indices.size() < work.rows()) { - throw CGException("Failed to select dummy derivatives! " - "The resulting system is probably singular for the provided data."); - } - - std::vector* > newDummies; - if (avoidConvertAlg2DifVars_) { - auto& graph = idxIdentify_->getGraph(); - const auto& varInfo = graph.getOriginalVariableInfo(); - - // add algebraic first - for (int i = 0; newDummies.size() < size_t(work.rows()) && i < qr.rank(); i++) { - Vnode* v = varsLocal[indices(i)]; - CPPADCG_ASSERT_UNKNOWN(v->originalVariable() != nullptr); - size_t tape = v->originalVariable()->tapeIndex(); - CPPADCG_ASSERT_UNKNOWN(tape < varInfo.size()); - if (varInfo[tape].getDerivative() < 0) { - // derivative of a variable which was originally algebraic only - newDummies.push_back(v); - } - } - // add remaining - for (int i = 0; newDummies.size() < size_t(work.rows()); i++) { - Vnode* v = varsLocal[indices(i)]; - CPPADCG_ASSERT_UNKNOWN(v->originalVariable() != nullptr); - size_t tape = v->originalVariable()->tapeIndex(); - CPPADCG_ASSERT_UNKNOWN(tape < varInfo.size()); - if (varInfo[tape].getDerivative() >= 0) { - // derivative of a variable which was already differential - newDummies.push_back(v); - } - } - - } else { - // use order provided by the householder column pivoting - for (int i = 0; i < work.rows(); i++) { - newDummies.push_back(varsLocal[indices(i)]); - } - } - - if (this->verbosity_ >= Verbosity::High) { - log() << "## new dummy derivatives: "; //"(condition = " << bestCond << "): "; - for (Vnode* it : newDummies) - log() << *it << "; "; - log() << " \n\n"; - } -#ifndef NDEBUG - for (Vnode* it : newDummies) { - CPPADCG_ASSERT_UNKNOWN(std::find(dummyD_.begin(), dummyD_.end(), it) == dummyD_.end()); - } -#endif - - dummyD_.insert(dummyD_.end(), newDummies.begin(), newDummies.end()); - } - - inline static void printModel(std::ostream& out, - CodeHandler& handler, - const std::vector& res, - const std::vector& varInfo, - const std::set& erasedVariables, - const std::set& erasedEquations) { - using std::vector; - - std::vector indepNames; - for (size_t p = 0; p < varInfo.size(); p++) { - if (erasedVariables.find(p) == erasedVariables.end()) { - // not erased from model - indepNames.push_back(varInfo[p].getName()); - } - } - CPPADCG_ASSERT_UNKNOWN(handler.getIndependentVariableSize() == indepNames.size()); - - LanguageC lang("double"); - vector resAux; - for (size_t p = 0; p < res.size(); ++p) { - if (erasedEquations.find(p) == erasedEquations.end()) { - resAux.push_back(res[p]); - } - } - std::vector depNames; - LangCCustomVariableNameGenerator nameGen(depNames, indepNames); - handler.generateCode(out, lang, resAux, nameGen); - } - - inline static void printGraphSparsity(std::ostream& out, - const std::vector& jacSparsity, - const std::map*>& tape2FreeVariables, - const std::vector*>& equations, - const size_t n) { - for (size_t e = 0; e < equations.size(); ++e) { - Enode* eq = equations[e]; - size_t count = 0; - for (const auto& it : tape2FreeVariables) { - if (jacSparsity[n * eq->index() + it.first]) { - if (count == 0) - out << "# Equation " << e << ": \t"; - out << " " << it.second->name(); - count++; - } - } - if (count > 0) - out << "\n"; - } - - out << std::endl; - } - - template - inline static void deleteVectorValues(std::vector& v) { - for (size_t i = 0; i < v.size(); i++) { - delete v[i]; - } - v.clear(); - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dummy_deriv_util.hpp b/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dummy_deriv_util.hpp deleted file mode 100644 index d458acaf1..000000000 --- a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/dummy_deriv_util.hpp +++ /dev/null @@ -1,144 +0,0 @@ -#ifndef CPPAD_CG_DUMMY_DERIV_UTIL_INCLUDED -#define CPPAD_CG_DUMMY_DERIV_UTIL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include - -namespace CppAD { -namespace cg { - -/** - * Sorts variable nodes according to the variable differentiation order - * - * @param i - * @param j - * @return true if i should come before j - */ -template -bool sortVnodesByOrder(Vnode* i, - Vnode* j) { - return (i->order() > j->order()); -} - -/** - * Utility class used to sort variables in the DAE - */ -class DaeVarOrderInfo { -public: - size_t originalIndex; - size_t originalIndex0; - bool hasDerivatives; - int order; -public: - inline DaeVarOrderInfo() : - originalIndex(0), - originalIndex0(0), - hasDerivatives(false), - order(-1) { - } - - inline DaeVarOrderInfo(size_t moriginalIndex, - size_t moriginalIndex0, - bool mhasDerivatives, - int morder) : - originalIndex(moriginalIndex), - originalIndex0(moriginalIndex0), - hasDerivatives(mhasDerivatives), - order(morder) { - } -}; - -/** - * Utility class used to sort equations in the DAE system - */ -class DaeEqOrderInfo { -public: - size_t originalIndex; - size_t originalIndex0; - bool differential; - int assignedVar; -public: - inline DaeEqOrderInfo() : - originalIndex(0), - originalIndex0(0), - differential(false), - assignedVar(-1) { - } - - inline DaeEqOrderInfo(size_t moriginalIndex, - size_t moriginalIndex0, - bool mdifferential, - int massignedVar) : - originalIndex(moriginalIndex), - originalIndex0(moriginalIndex0), - differential(mdifferential), - assignedVar(massignedVar) { - } -}; - -/** - * Sorts variables based on the differentiation order, whether they are - * algebraic or differential and the order in the original model - * - * @param i - * @param j - * @return true if i should come before j - */ -inline bool sortVariablesByOrder(const DaeVarOrderInfo& i, - const DaeVarOrderInfo& j) { - if (j.order < i.order) { - return true; - } else if (j.order > i.order) { - return false; - } else if (i.hasDerivatives == j.hasDerivatives) { - return j.originalIndex > i.originalIndex; - } else { - return i.hasDerivatives; - } -} - -/** - * Sorts equations according to the equation type (differential/algebraic) - * and original index - * - * @param i - * @param j - * @return true if i should come before j - */ -inline bool sortEquationByAssignedOrder2(const DaeEqOrderInfo& i, - const DaeEqOrderInfo& j) { - if (i.differential) { - if (j.differential) - return i.assignedVar < j.assignedVar; - else - return true; - } else { - if (j.differential) { - return false; - } else { - if (i.originalIndex0 == j.originalIndex0) { - return i.originalIndex == j.originalIndex0; - } else { - return i.originalIndex0 < j.originalIndex0; - } - } - } -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/pantelides.hpp b/ct_core/include/ct/external/cppad/cg/dae_index_reduction/pantelides.hpp deleted file mode 100644 index e583cb098..000000000 --- a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/pantelides.hpp +++ /dev/null @@ -1,203 +0,0 @@ -#ifndef CPPAD_CG_PANTELIDES_INCLUDED -#define CPPAD_CG_PANTELIDES_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include -#include - -namespace CppAD { -namespace cg { - -/** - * Pantelides DAE index reduction algorithm - */ -template -class Pantelides : public DaeStructuralIndexReduction { -protected: - typedef CppAD::cg::CG CGBase; - typedef CppAD::AD ADCG; -protected: - // avoids having to type this->graph_ - using DaeStructuralIndexReduction::graph_; - // typical values used to avoid NaNs in the tape validation by CppAD - std::vector x_; - // whether or not reduceIndex() has been called - bool reduced_; - AugmentPathDepthLookahead defaultAugmentPath_; - AugmentPath* augmentPath_; -public: - - /** - * Creates the DAE index reduction algorithm that implements the - * Pantelides method. - * - * @param fun The original model (potentially high index) - * @param varInfo The DAE system variable information (in the same order - * as in the tape) - * @param eqName Equation names (it can be an empty vector) - * @param x Typical variable values (used to avoid NaNs in CppAD checks) - */ - Pantelides(ADFun >& fun, - const std::vector& varInfo, - const std::vector& eqName, - const std::vector& x) : - DaeStructuralIndexReduction(fun, varInfo, eqName), - x_(x), - reduced_(false), - augmentPath_(&defaultAugmentPath_) { - - } - - Pantelides(const Pantelides& p) = delete; - - Pantelides& operator=(const Pantelides& p) = delete; - - virtual ~Pantelides() { - } - - AugmentPath& getAugmentPath() const { - return *augmentPath_; - } - - void setAugmentPath(AugmentPath& a) const { - augmentPath_ = &a; - } - - virtual inline std::unique_ptr>> reduceIndex(std::vector& newVarInfo, - std::vector& equationInfo) override { - if (reduced_) - throw CGException("reduceIndex() can only be called once!"); - - if (this->verbosity_ >= Verbosity::Low) - log() << "######## Pantelides method ########\n"; - - augmentPath_->setLogger(*this); - - reduced_ = true; - - detectSubset2Dif(); - - if (this->verbosity_ >= Verbosity::Low) { - graph_.printResultInfo("Pantelides"); - - log() << "Structural index: " << graph_.getStructuralIndex() << std::endl; - } - - std::unique_ptr> reducedFun(graph_.generateNewModel(newVarInfo, equationInfo, x_)); - - return reducedFun; - } - -protected: - using DaeStructuralIndexReduction::log; - - /** - * - */ - inline void detectSubset2Dif() { - auto& vnodes = graph_.variables(); - auto& enodes = graph_.equations(); - - Enode* ll; - - if (this->verbosity_ >= Verbosity::High) - graph_.printDot(this->log()); - - size_t Ndash = enodes.size(); - for (size_t k = 0; k < Ndash; k++) { - Enode* i = enodes[k]; - - if (this->verbosity_ >= Verbosity::High) - log() << "Outer loop: equation k = " << *i << "\n"; - - bool pathfound = false; - while (!pathfound) { - - /** - * delete all V-nodes with A!=0 and their incident edges - * from the graph - */ - for (Vnode* jj : vnodes) { - if (!jj->isDeleted() && jj->derivative() != nullptr) { - jj->deleteNode(log(), this->verbosity_); - } - } - - graph_.uncolorAll(); - - pathfound = augmentPath_->augmentPath(*i); - - if (!pathfound) { - const size_t vsize = vnodes.size(); // the size might change - for (size_t l = 0; l < vsize; ++l) { - Vnode* jj = vnodes[l]; - if (jj->isColored() && !jj->isDeleted()) { - // add new variable derivatives of colored variables - graph_.createDerivate(*jj); - } - } - - const size_t esize = enodes.size(); // the size might change - for (size_t l = 0; l < esize; l++) { - ll = enodes[l]; - if (ll->isColored()) { - // add new derivative equations for colored equations and create edges - graph_.createDerivate(*ll); - } - } - - // structural check to avoid infinite recursion - for (size_t l = esize; l < enodes.size(); l++) { - ll = enodes[l]; - const std::vector*>& nvars = ll->originalVariables(); - bool ok = false; - for (Vnode* js : nvars) { - if (js->equations().size() > 1) { - ok = true; - break; - } - } - if (!ok) - throw CGException("Invalid equation structure. The model appears to be over-defined."); - } - - for (Vnode* jj : vnodes) { - if (jj->isColored() && !jj->isDeleted()) { - Vnode* jDiff = jj->derivative(); - jDiff->setAssignmentEquation(*jj->assignmentEquation()->derivative(), log(), this->verbosity_); - } - } - - i = i->derivative(); - - if (this->verbosity_ >= Verbosity::High) { - log() << "Set current equation to (i=" << i->index() << ") " << *i << "\n"; - - graph_.printDot(this->log()); - } - } - } - - } - - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/simple_logger.hpp b/ct_core/include/ct/external/cppad/cg/dae_index_reduction/simple_logger.hpp deleted file mode 100644 index f3ae33768..000000000 --- a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/simple_logger.hpp +++ /dev/null @@ -1,65 +0,0 @@ -#ifndef CPPAD_CG_SIMPLE_LOGGER_INCLUDED -#define CPPAD_CG_SIMPLE_LOGGER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * A very simple logger - */ -class SimpleLogger { -protected: - // verbosity level - Verbosity verbosity_; - // output stream used for logging - std::ostream* log_; -public: - - /** - * Creates a new simple logger - */ - inline SimpleLogger() : - verbosity_(Verbosity::None), - log_(&std::cout) { - } - - inline virtual ~SimpleLogger() { - } - - inline std::ostream& log() const { - return *log_; - } - - inline void setLog(std::ostream& out) { - log_ = &out; - } - - inline void setVerbosity(Verbosity verbosity) { - verbosity_ = verbosity; - } - - inline Verbosity getVerbosity() const { - return verbosity_; - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif - diff --git a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/soares_secchi.hpp b/ct_core/include/ct/external/cppad/cg/dae_index_reduction/soares_secchi.hpp deleted file mode 100644 index 227c36975..000000000 --- a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/soares_secchi.hpp +++ /dev/null @@ -1,242 +0,0 @@ -#ifndef CPPAD_CG_SOARES_SECCHI_HPP -#define CPPAD_CG_SOARES_SECCHI_HPP -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include -#include -#include - -namespace CppAD { -namespace cg { - -/** - * Soares Secchi method for DAE structural index reduction - */ -template -class SoaresSecchi : public DaeStructuralIndexReduction { -protected: - typedef CppAD::cg::CG CGBase; - typedef CppAD::AD ADCG; -protected: - // avoids having to type this->graph_ - using DaeStructuralIndexReduction::graph_; - // typical values used to avoid NaNs in the tape validation by CppAD - std::vector x_; - /** - * the last equations added to graph - * (equations used to create the ODE or DAE with index 1) - */ - std::set*> lastAddEq_; - // whether or not reduceIndex() has been called - bool reduced_; - // - AugmentPathDepthLookahead defaultAugmentPath_; - AugmentPathDepthLookaheadA defaultAugmentPathA_; - AugmentPath* augmentPath_; - AugmentPath* augmentPathA_; -public: - - /** - * Creates the DAE index reduction algorithm that implements the - * Soares Secchi method. - * - * @param fun The original model (potentially high index) - * @param varInfo The DAE system variable information (in the same order - * as in the tape) - * @param eqName Equation names (it can be an empty vector) - * @param x typical variable values (used to avoid NaNs in CppAD checks) - */ - SoaresSecchi(ADFun >& fun, - const std::vector& varInfo, - const std::vector& eqName, - const std::vector& x) : - DaeStructuralIndexReduction(fun, varInfo, eqName), - x_(x), - reduced_(false), - augmentPath_(&defaultAugmentPath_), - augmentPathA_(&defaultAugmentPathA_){ - - } - - SoaresSecchi(const SoaresSecchi& p) = delete; - - SoaresSecchi& operator=(const SoaresSecchi& p) = delete; - - virtual ~SoaresSecchi() { - } - - AugmentPath& getAugmentPath() const { - return *augmentPath_; - } - - void setAugmentPath(AugmentPath& a) const { - augmentPath_ = &a; - } - - /** - * Defines whether or not original names saved by using - * CppAD::PrintFor(0, "", val, name) - * should be kept by also adding PrintFor operations in the reduced model. - */ - inline void setPreserveNames(bool p) { - graph_.setPreserveNames(p); - } - - /** - * Whether or not original names saved by using - * CppAD::PrintFor(0, "", val, name) - * should be kept by also adding PrintFor operations in the reduced model. - */ - inline bool isPreserveNames() const { - return graph_.isPreserveNames(); - } - - /** - * Performs the DAE differentiation index reductions - * - * @param newVarInfo Variable related information of the reduced index - * model - * @param equationInfo Equation related information of the reduced index - * model - * @return the reduced index model (must be deleted by user) - * @throws CGException on failure - */ - virtual inline std::unique_ptr>> reduceIndex(std::vector& newVarInfo, - std::vector& equationInfo) override { - if (reduced_) - throw CGException("reduceIndex() can only be called once!"); - - if (this->verbosity_ >= Verbosity::High) - log() << "######## Soares Secchi method ########\n"; - - augmentPath_->setLogger(*this); - augmentPathA_->setLogger(*this); - - reduced_ = true; - - // detects which equations have to be differentiated to get an ODE - detectSubset2Dif(); - - // we want an index 1 DAE (ignore the last equations added to the graph) - for(const Enode* i: lastAddEq_) { - graph_.remove(*i); - } - - if (this->verbosity_ >= Verbosity::Low) { - graph_.printResultInfo("Soares Secchi"); - - log() << "Structural index: " << graph_.getStructuralIndex() << std::endl; - } - - std::unique_ptr> reducedFun(graph_.generateNewModel(newVarInfo, equationInfo, x_)); - - return reducedFun; - } - - /** - * Provides the differentiation index. It can only be called after - * reduceIndex(). - * - * @return the DAE differentiation index. - * @throws CGException - */ - inline size_t getStructuralIndex() const { - return graph_.getStructuralIndex(); - } - -protected: - using DaeStructuralIndexReduction::log; - - /** - * - */ - inline void detectSubset2Dif() { - auto& vnodes = graph_.variables(); - auto& enodes = graph_.equations(); - - std::set*> marked; - std::set*> lastMarked; - - if (this->verbosity_ >= Verbosity::High) - graph_.printDot(this->log()); - - while (true) { - // augment the matching one by one - for (size_t k = 0; k < enodes.size(); k++) { - Enode* i = enodes[k]; - - if (this->verbosity_ >= Verbosity::High) - log() << "Outer loop: equation k = " << *i << "\n"; - - if (i->assignmentVariable() != nullptr) { - continue; - } - - bool pathFound = augmentPathA_->augmentPath(*i); - if (!pathFound) { - - for (Enode* ii: enodes) { - // mark colored equations to be differentiated - if (ii->isColored() && ii->derivative() == nullptr) { - marked.insert(ii); - - // uncolor equations - ii->uncolor(); - } - } - - pathFound = augmentPath_->augmentPath(*i); - if (!pathFound) { - throw CGException("Singular system detected."); - } - - for (auto* jj: vnodes) - jj->uncolor(); - - } else { - for (auto* ii: enodes) - ii->uncolor(); - } - } - - if (marked.empty()) - break; - - // diff all MARKED equations - for (Enode* i: marked) { - graph_.createDerivate(*i, false); - } - - if (this->verbosity_ >= Verbosity::High) - graph_.printDot(this->log()); - - lastMarked.swap(marked); - marked.clear(); - } - - lastAddEq_.clear(); - for (const Enode* i: lastMarked) { - lastAddEq_.insert(i->derivative()); - } - - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/time_diff.hpp b/ct_core/include/ct/external/cppad/cg/dae_index_reduction/time_diff.hpp deleted file mode 100644 index 1d2ae34fe..000000000 --- a/ct_core/include/ct/external/cppad/cg/dae_index_reduction/time_diff.hpp +++ /dev/null @@ -1,180 +0,0 @@ -#ifndef CPPAD_CG_TIME_DIFF_INCLUDED -#define CPPAD_CG_TIME_DIFF_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -// ---------------------------------------------------------------------- -// forward mode routine called by CppAD for y = f(x, dxdt, t) - -template -bool time_diff_forward(size_t id, - size_t order, - size_t n, - size_t m, - const CppAD::vector& vx, - CppAD::vector& vzy, - const CppAD::vector >& tx, - CppAD::vector >& tzy) { - CPPADCG_ASSERT_UNKNOWN(n == 3); // [x, dxdt, t] - CPPADCG_ASSERT_UNKNOWN(m == 1); - CPPADCG_ASSERT_UNKNOWN(tx.size() >= (order + 1) * n); - CPPADCG_ASSERT_UNKNOWN(tzy.size() >= (order + 1) * m); - - size_t n_order = order + 1; - const size_t xIndex = 0; // index of the variable in the argument list - const size_t dxdtIndex = 1; // index of the time derivative variable in the argument list - const size_t timeIndex = 2; // index of the time variable in the argument list - - // check if this is during the call to time_var(id, ax, ay) - if (vx.size() > 0) { - CPPADCG_ASSERT_UNKNOWN(vx.size() >= n); - CPPADCG_ASSERT_UNKNOWN(vzy.size() >= m); - - vzy[0] = vx[0] || vx[1] || vx[2]; - } - - if (order == 0) { - tzy[0] = tx[0]; - } else if (order == 1) { - const CG& ttime = tx[timeIndex * n_order + order]; // - const CG& txx = tx[xIndex * n_order + order]; // - CPPADCG_ASSERT_UNKNOWN(ttime.isParameter()); - CPPADCG_ASSERT_UNKNOWN(txx.isParameter()); - if (ttime.getValue() > 0) { - CPPADCG_ASSERT_UNKNOWN(txx.getValue() == 0); - tzy[1] = ttime * tx[dxdtIndex * n_order + 0]; // transform x(t) into dx(t)/dt - } else { - tzy[1] = txx; // do nothing - } - - } else { - return false; // not implemented - } - - // All orders are implemented and there are no possible errors - return true; -} -// ---------------------------------------------------------------------- -// reverse mode routine called by CppAD for y = f(x, dxdt, t) - -template -bool time_diff_reverse(size_t id, - size_t order, - size_t n, - size_t m, - const CppAD::vector >& tx, - const CppAD::vector >& tzy, - CppAD::vector >& px, - const CppAD::vector >& pzy) { - - CPPADCG_ASSERT_UNKNOWN(n == 3); // [x, dxdt, t] - CPPADCG_ASSERT_UNKNOWN(m == 1); - CPPADCG_ASSERT_UNKNOWN(tx.size() >= (order + 1) * n); - CPPADCG_ASSERT_UNKNOWN(tzy.size() >= (order + 1) * m); - CPPADCG_ASSERT_UNKNOWN(px.size() >= (order + 1) * n); - - CG* pxx = &px[0]; - CG* pdxdt = &px[order + 1]; - CG* pt = &px[2 * (order + 1)]; - - //const CG* txx = &tx[0]; - const CG* tdxdt = &tx[order + 1]; - //const CG* tt = &tx[2 * (order + 1)]; - - if (order == 0) { - pxx[0] = pzy[0] * 1.0; - pdxdt[0] = 0.0; - pt[0] = pzy[0] * tdxdt[0]; - return true; - } - - return false; // not implemented yet -} -// ---------------------------------------------------------------------- -// forward Jacobian sparsity routine called by CppAD - -template -bool time_diff_for_jac_sparse(size_t id, - size_t n, - size_t m, - size_t q, - const CppAD::vector< std::set >& r, - CppAD::vector< std::set >& s) { - CPPADCG_ASSERT_UNKNOWN(n == 3); - CPPADCG_ASSERT_UNKNOWN(m == 1); - CPPADCG_ASSERT_UNKNOWN(r.size() >= n); - CPPADCG_ASSERT_UNKNOWN(s.size() >= m); - - // sparsity for z and y are the same as for x - s[0] = r[0]; // x - s[0].insert(r[1].begin(), r[1].end()); // dxdt - s[0].insert(r[2].begin(), r[2].end()); // t - - return true; -} -// ---------------------------------------------------------------------- -// reverse Jacobian sparsity routine called by CppAD - -template -bool time_diff_rev_jac_sparse(size_t id, - size_t n, - size_t m, - size_t q, - CppAD::vector< std::set >& r, - const CppAD::vector< std::set >& s) { - CPPADCG_ASSERT_UNKNOWN(n == 3); - CPPADCG_ASSERT_UNKNOWN(m == 1); - CPPADCG_ASSERT_UNKNOWN(r.size() >= n); - CPPADCG_ASSERT_UNKNOWN(s.size() >= m); - - r[0] = s[0]; - r[2] = s[0]; - - return false; -} -// ---------------------------------------------------------------------- -// reverse Hessian sparsity routine called by CppAD - -template -bool time_diff_rev_hes_sparse(size_t id, - size_t n, - size_t m, - size_t q, - const CppAD::vector< std::set >& r, - const CppAD::vector& s, - CppAD::vector& t, - const CppAD::vector< std::set >& u, - CppAD::vector< std::set >& v) { - return false; -} -// --------------------------------------------------------------------- -// Declare the AD > routine time_var(id, ax, ay) -template -CPPAD_USER_ATOMIC(time_var, - std::vector, - cg::CG, - CppAD::cg::time_diff_forward, - CppAD::cg::time_diff_reverse, - CppAD::cg::time_diff_for_jac_sparse, - CppAD::cg::time_diff_rev_jac_sparse, - CppAD::cg::time_diff_rev_hes_sparse) - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/debug.hpp b/ct_core/include/ct/external/cppad/cg/debug.hpp deleted file mode 100644 index 468e74d94..000000000 --- a/ct_core/include/ct/external/cppad/cg/debug.hpp +++ /dev/null @@ -1,23 +0,0 @@ -#ifndef CPPAD_CG_DEBUG_INCLUDED -#define CPPAD_CG_DEBUG_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#ifndef CPPADCG_DEBUG_VARIABLE_CHECKID -#define CPPADCG_DEBUG_VARIABLE_CHECKID(id) -#endif - -#endif - diff --git a/ct_core/include/ct/external/cppad/cg/declare_cg.hpp b/ct_core/include/ct/external/cppad/cg/declare_cg.hpp deleted file mode 100644 index 7b53ff2f5..000000000 --- a/ct_core/include/ct/external/cppad/cg/declare_cg.hpp +++ /dev/null @@ -1,455 +0,0 @@ -#ifndef CPPAD_CG_DECLARE_CG_INCLUDED -#define CPPAD_CG_DECLARE_CG_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -// forward declarations -namespace CppAD { - -template -class vector; - -template -class AD; - -template -class ADFun; - -namespace cg { - -/*************************************************************************** - * Atomics - **************************************************************************/ -template -class BaseAbstractAtomicFun; - -template -class CGAbstractAtomicFun; - -template -class CGAtomicFun; - -/*************************************************************************** - * Core - **************************************************************************/ -template -class CodeHandler; - -template -class CodeHandlerVectorSync; - -template -class CodeHandlerVector; - -template -class CG; - -template -struct OperationPathNode; - -template -class PathNodeEdges; - -template -class BidirGraph; - -template -class ScopePathElement; - -/*************************************************************************** - * Nodes - **************************************************************************/ -template -class OperationNode; - -template -class IndexOperationNode; - -template -class IndexAssignOperationNode; - -template -class LoopStartOperationNode; - -template -class LoopEndOperationNode; - -/*************************************************************************** - * Loops - **************************************************************************/ -template -class EquationPattern; - -template -class DependentPatternMatcher; - -template -class Loop; - -template -class LoopFreeModel; - -template -class LoopModel; - -template -class IndexedDependentLoopInfo; - -class IndexPattern; -class LinearIndexPattern; -class Plane2DIndexPattern; -class RandomIndexPattern; -class SectionedIndexPattern; - -/*************************************************************************** - * Languages - **************************************************************************/ - -template -class LanguageC; - -template -class VariableNameGenerator; - -template -class LangCDefaultVariableNameGenerator; - -template -class LangCCustomVariableNameGenerator; - -/*************************************************************************** - * Models - **************************************************************************/ -template -class GenericModel; - -template -class ModelLibraryProcessor; - -template -class FunctorGenericModel; - -/*************************************************************************** - * Dynamic model compilation - **************************************************************************/ - -template -class CCompiler; - -template -class DynamicLib; - -template -class ModelCSourceGen; - -template -class ModelLibraryCSourceGen; - -#if CPPAD_CG_SYSTEM_LINUX -template -class LinuxDynamicLibModel; - -template -class LinuxDynamicLib; -#endif - -/*************************************************************************** - * Index reduction classes - **************************************************************************/ -template -class Enode; - -template -class Vnode; - -template -class Evaluator; - -/*************************************************************************** - * Utilities - **************************************************************************/ - -template -class SmartVectorPointer; - -template -class SmartListPointer; - -template -class SmartMapValuePointer; - -template -class ArrayWrapper; - -template -inline void print(const Base& v); - -template -inline void print(const std::map& m); - -template -inline void print(const std::set& s); - -template -inline void print(const std::set& s); - -template -inline void print(const std::vector& v); - -/** - * arithmetic - */ -template -CG operator+(const CG& left, const CG& right); - -template -CG operator-(const CG& left, const CG& right); - -template -CG operator*(const CG& left, const CG& right); - -template -CG operator/(const CG& left, const CG& right); - -/** - * comparisons - */ -template -bool operator==(const CG& left, const CG& right); - -template -bool operator!=(const CG& left, const CG& right); - -template -bool operator<(const CG& left, const CG& right); - -template -bool operator<=(const CG& left, const CG& right); - -template -bool operator>(const CG& left, const CG& right); - -template -bool operator>=(const CG& left, const CG& right); - -template -bool operator!=(const CG& left, double right); - -/*************************************************************************** - * Index reduction functions - **************************************************************************/ - -template -inline std::ostream& operator<<(std::ostream& os, const Enode& i); - -template -inline std::ostream& operator<<(std::ostream& os, const Vnode& j); - -/*************************************************************************** - * Enums - **************************************************************************/ - -/** - * Verbosity level for print-outs - */ -enum class Verbosity { - None, Low, High -}; - -/** - * Automatic Differentiation modes used to determine the Jacobian - */ -enum class JacobianADMode { - Forward, Reverse, Automatic -}; - -/** - * Index pattern types - */ -enum class IndexPatternType { - Linear, // y = (x / dx) * dy + b - Sectioned, // several index patterns - Random1D, - Random2D, - Plane2D // y = f(x) + f(z) -}; - -} // END cg namespace - -/*************************************************************************** - * - **************************************************************************/ -// order determining functions, see ordered.hpp -template -bool GreaterThanZero(const cg::CG& x); - -template -bool GreaterThanOrZero(const cg::CG& x); - -template -bool LessThanZero(const cg::CG& x); - -template -bool LessThanOrZero(const cg::CG& x); - -template -bool abs_geq(const cg::CG& x, const cg::CG& y); - -// The identical property functions, see identical.hpp -template -inline bool IdenticalPar(const cg::CG& x) throw (cg::CGException); - -template -bool IdenticalZero(const cg::CG& x) throw (cg::CGException); - -template -bool IdenticalOne(const cg::CG& x) throw (cg::CGException); - -template -bool IdenticalEqualPar(const cg::CG& x, const cg::CG& y); - -// EqualOpSeq function -template -bool EqualOpSeq(const cg::CG& u, const cg::CG& v); - -// NearEqual function -template -bool NearEqual(const cg::CG& x, const cg::CG& y, const Base& r, const Base& a); - -template -bool NearEqual(const Base& x, const cg::CG& y, const Base& r, const Base& a); - -template -bool NearEqual(const cg::CG& x, const Base& y, const Base& r, const Base& a); - -template -inline bool isnan(const cg::CG& s); - -template -int Integer(const cg::CG& x); - -template -cg::CG CondExp(cg::CGOpCode op, - const cg::CG& left, const cg::CG& right, - const cg::CG& trueCase, const cg::CG& falseCase, - bool (*compare)(const Base&, const Base&)); - -/** - * Math functions - */ -template -inline cg::CG sign(const cg::CG& x); - -// power function -template -inline cg::CG pow(const cg::CG& x, const cg::CG& y); -template -inline cg::CG pow(const Base& x, const cg::CG& y); -template -inline cg::CG pow(const cg::CG& x, const Base& y); - -// absolute value -template -inline cg::CG abs(const cg::CG& x); - -template -inline cg::CG fabs(const cg::CG& x); - -// inverse cosine -template -inline cg::CG acos(const cg::CG& x); - -// inverse sine -template -inline cg::CG asin(const cg::CG& x); - -// inverse tangent -template -inline cg::CG atan(const cg::CG& x); - -// cosine -template -inline cg::CG cos(const cg::CG& x); - -// hyperbolic cosine -template -inline cg::CG cosh(const cg::CG& x); - -// exponential -template -inline cg::CG exp(const cg::CG& x); - -// natural logarithm -template -inline cg::CG log(const cg::CG& x); - -// sine -template -inline cg::CG sin(const cg::CG& x); - -// hyperbolic sine -template -inline cg::CG sinh(const cg::CG& x); - -// square root -template -inline cg::CG sqrt(const cg::CG& x); - -// tangent -template -inline cg::CG tan(const cg::CG& x); - -// hyperbolic tangent -template -inline cg::CG tanh(const cg::CG& x); - -#if CPPAD_USE_CPLUSPLUS_2011 -/** - * c++11 functions - */ -// error function -template -inline cg::CG erf(const cg::CG& x); - -// inverse hyperbolic sin -template -inline cg::CG asinh(const cg::CG& x); - -// inverse hyperbolic cosine -template -inline cg::CG acosh(const cg::CG& x); - -// inverse hyperbolic tangent -template -inline cg::CG atanh(const cg::CG& x); - -// exponential of x minus one -template -inline cg::CG expm1(const cg::CG& x); - -// logarithm of one plus x -template -inline cg::CG log1p(const cg::CG& x); -#endif - -} // END CppAD namespace - -/** - * loops namespace - */ -#include - -#endif - diff --git a/ct_core/include/ct/external/cppad/cg/declare_cg_loops.hpp b/ct_core/include/ct/external/cppad/cg/declare_cg_loops.hpp deleted file mode 100644 index 6e6c71db3..000000000 --- a/ct_core/include/ct/external/cppad/cg/declare_cg_loops.hpp +++ /dev/null @@ -1,147 +0,0 @@ -#ifndef CPPAD_CG_DECLARE_CG_LOOPS_INCLUDED -#define CPPAD_CG_DECLARE_CG_LOOPS_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -// forward declarations -namespace CppAD { -namespace cg { - -template -class vector; - -namespace loops { - -typedef std::pair SizeN1stIt; - -typedef std::pair pairss; - -class JacobianWithLoopsRowInfo; - -class HessianElement; - -template -class LoopNonIndexedLocator; - -template -class IfBranchInfo; - -template -class IfElseInfo; - -template -class JacobianTermContrib; - -template -class JacobianColGroup; - -template -class HessianWithLoopsInfo; - -template -class HessianWithLoopsEquationGroupInfo; - -template -class HessianRowGroup; - -class ArrayGroup; - -template -inline std::vector > createIndexedIndependents(CodeHandler& handler, - LoopModel& loop, - IndexOperationNode& iterationIndexOp); - -template -inline std::vector > createLoopIndependentVector(CodeHandler& handler, - LoopModel& loop, - const std::vector >& indexedIndeps, - const std::vector >& nonIndexedIndeps, - const std::vector >& nonIndexedTmps); - -template -inline std::vector > createLoopDependentVector(CodeHandler& handler, - LoopModel& loop, - IndexOperationNode& iterationIndexOp); - -template -inline CG createLoopDependentFunctionResult(CodeHandler& handler, - size_t i, const CG& val, IndexPattern* ip, - IndexOperationNode& iterationIndexOp); - -template -inline LoopEndOperationNode* createLoopEnd(CodeHandler& handler, - LoopStartOperationNode& loopStart, - const std::vector, IndexPattern*> >& indexedLoopResults, - const std::set*>& indexesOps, - size_t assignOrAdd); - -template -inline void moveNonIndexedOutsideLoop(LoopStartOperationNode& loopStart, - LoopEndOperationNode& loopEnd); - -template -inline bool findNonIndexedNodes(OperationNode& node, - std::set*>& nonIndexed, - const OperationNode& loopIndex); - -template -inline IfElseInfo* findExistingIfElse(std::vector >& ifElses, - const std::map > >& first2Iterations); - -inline std::vector createIndexConditionExpression(const std::set& iterations, - const std::set& usedIter, - size_t maxIter); - -template -inline OperationNode* createIndexConditionExpressionOp(CodeHandler& handler, - const std::set& iterations, - const std::set& usedIter, - size_t maxIter, - IndexOperationNode& iterationIndexOp); - -template -inline void determineForRevUsagePatterns(const std::map*, std::map > > >& loopGroups, - const std::map > >& userElLocation, - const std::map& ordered, - std::map*, std::map > >& loopCalls, - SmartVectorPointer& garbage); - -template -void generateFunctionDeclarationSourceLoopForRev(std::ostringstream& cache, - LanguageC& langC, - const std::string& modelName, - const std::string& keyName, - const std::map*, std::map > > >& _loopRev2Groups, - void (*generateFunctionNameLoopRev2)(std::ostringstream& cache, const std::string& modelName, const LoopModel& loop, size_t g)); - -template -inline void generateLoopForJacHes(ADFun >& fun, - const std::vector >& x, - const std::vector > >& vw, - std::vector >& y, - const std::vector >& jacSparsity, - const std::vector >& jacEvalSparsity, - std::vector > >& jac, - const std::vector >& hesSparsity, - const std::vector >& hesEvalSparsity, - std::vector > > >& vhess, - bool constainsAtomics); - -} // END loops namespace - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/default.hpp b/ct_core/include/ct/external/cppad/cg/default.hpp deleted file mode 100644 index 3d0f7a943..000000000 --- a/ct_core/include/ct/external/cppad/cg/default.hpp +++ /dev/null @@ -1,103 +0,0 @@ -#ifndef CPPAD_CG_DEFAULT_INCLUDED -#define CPPAD_CG_DEFAULT_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Creates a parameter with a zero value - */ -template -inline CG::CG() : - node_(nullptr), - value_(new Base(0.0)) { -} - -template -inline CG::CG(OperationNode& node) : - node_(&node), - value_(nullptr) { -} - -template -inline CG::CG(const Argument& arg) : - node_(arg.getOperation()), - value_(arg.getParameter() != nullptr ? new Base(*arg.getParameter()) : nullptr) { - -} - -/** - * Creates a parameter with the given value - */ -template -inline CG::CG(const Base &b) : - node_(nullptr), - value_(new Base(b)) { -} - -/** - * Copy constructor - */ -template -inline CG::CG(const CG& orig) : - node_(orig.node_), - value_(orig.value_ != nullptr ? new Base(*orig.value_) : nullptr) { -} - -/** - * Creates a parameter with the given value - */ -template -inline CG& CG::operator=(const Base &b) { - node_ = nullptr; - if (value_ != nullptr) { - *value_ = b; - } else { - value_ = new Base(b); - } - return *this; -} - -template -inline CG& CG::operator=(const CG &rhs) { - if (&rhs == this) { - return *this; - } - node_ = rhs.node_; - if (rhs.value_ != nullptr) { - if (value_ != nullptr) { - *value_ = *rhs.value_; - } else { - value_ = new Base(*rhs.value_); - } - } else { - delete value_; - value_ = nullptr; - } - - return *this; -} - -template -CG::~CG() { - delete value_; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/epl-v10.txt b/ct_core/include/ct/external/cppad/cg/epl-v10.txt deleted file mode 100644 index 292eacbef..000000000 --- a/ct_core/include/ct/external/cppad/cg/epl-v10.txt +++ /dev/null @@ -1,230 +0,0 @@ - - -Eclipse Public License - v 1.0 - -THE ACCOMPANYING PROGRAM IS PROVIDED UNDER THE TERMS OF THIS ECLIPSE -PUBLIC LICENSE ("AGREEMENT"). ANY USE, REPRODUCTION OR -DISTRIBUTION OF THE PROGRAM CONSTITUTES RECIPIENT'S ACCEPTANCE OF THIS -AGREEMENT. - -1. DEFINITIONS - -"Contribution" means: - - a) in the case of the initial Contributor, the initial - code and documentation distributed under this Agreement, and - b) in the case of each subsequent Contributor: - i) changes to the Program, and - ii) additions to the Program; - where such changes and/or additions to the Program - originate from and are distributed by that particular Contributor. A - Contribution 'originates' from a Contributor if it was added to the - Program by such Contributor itself or anyone acting on such - Contributor's behalf. Contributions do not include additions to the - Program which: (i) are separate modules of software distributed in - conjunction with the Program under their own license agreement, and (ii) - are not derivative works of the Program. - -"Contributor" means any person or entity that distributes -the Program. - -"Licensed Patents" mean patent claims licensable by a -Contributor which are necessarily infringed by the use or sale of its -Contribution alone or when combined with the Program. - -"Program" means the Contributions distributed in accordance -with this Agreement. - -"Recipient" means anyone who receives the Program under -this Agreement, including all Contributors. - -2. GRANT OF RIGHTS - - a) Subject to the terms of this Agreement, each - Contributor hereby grants Recipient a non-exclusive, worldwide, - royalty-free copyright license to reproduce, prepare derivative works - of, publicly display, publicly perform, distribute and sublicense the - Contribution of such Contributor, if any, and such derivative works, in - source code and object code form. - - b) Subject to the terms of this Agreement, each - Contributor hereby grants Recipient a non-exclusive, worldwide, - royalty-free patent license under Licensed Patents to make, use, sell, - offer to sell, import and otherwise transfer the Contribution of such - Contributor, if any, in source code and object code form. This patent - license shall apply to the combination of the Contribution and the - Program if, at the time the Contribution is added by the Contributor, - such addition of the Contribution causes such combination to be covered - by the Licensed Patents. The patent license shall not apply to any other - combinations which include the Contribution. No hardware per se is - licensed hereunder. - - c) Recipient understands that although each Contributor - grants the licenses to its Contributions set forth herein, no assurances - are provided by any Contributor that the Program does not infringe the - patent or other intellectual property rights of any other entity. Each - Contributor disclaims any liability to Recipient for claims brought by - any other entity based on infringement of intellectual property rights - or otherwise. As a condition to exercising the rights and licenses - granted hereunder, each Recipient hereby assumes sole responsibility to - secure any other intellectual property rights needed, if any. For - example, if a third party patent license is required to allow Recipient - to distribute the Program, it is Recipient's responsibility to acquire - that license before distributing the Program. - - d) Each Contributor represents that to its knowledge it - has sufficient copyright rights in its Contribution, if any, to grant - the copyright license set forth in this Agreement. - -3. REQUIREMENTS - -A Contributor may choose to distribute the Program in object code -form under its own license agreement, provided that: - - a) it complies with the terms and conditions of this - Agreement; and - - b) its license agreement: - - i) effectively disclaims on behalf of all Contributors - all warranties and conditions, express and implied, including warranties - or conditions of title and non-infringement, and implied warranties or - conditions of merchantability and fitness for a particular purpose; - - ii) effectively excludes on behalf of all Contributors - all liability for damages, including direct, indirect, special, - incidental and consequential damages, such as lost profits; - - iii) states that any provisions which differ from this - Agreement are offered by that Contributor alone and not by any other - party; and - - iv) states that source code for the Program is available - from such Contributor, and informs licensees how to obtain it in a - reasonable manner on or through a medium customarily used for software - exchange. - -When the Program is made available in source code form: - - a) it must be made available under this Agreement; and - - b) a copy of this Agreement must be included with each - copy of the Program. - -Contributors may not remove or alter any copyright notices contained -within the Program. - -Each Contributor must identify itself as the originator of its -Contribution, if any, in a manner that reasonably allows subsequent -Recipients to identify the originator of the Contribution. - -4. COMMERCIAL DISTRIBUTION - -Commercial distributors of software may accept certain -responsibilities with respect to end users, business partners and the -like. While this license is intended to facilitate the commercial use of -the Program, the Contributor who includes the Program in a commercial -product offering should do so in a manner which does not create -potential liability for other Contributors. Therefore, if a Contributor -includes the Program in a commercial product offering, such Contributor -("Commercial Contributor") hereby agrees to defend and -indemnify every other Contributor ("Indemnified Contributor") -against any losses, damages and costs (collectively "Losses") -arising from claims, lawsuits and other legal actions brought by a third -party against the Indemnified Contributor to the extent caused by the -acts or omissions of such Commercial Contributor in connection with its -distribution of the Program in a commercial product offering. The -obligations in this section do not apply to any claims or Losses -relating to any actual or alleged intellectual property infringement. In -order to qualify, an Indemnified Contributor must: a) promptly notify -the Commercial Contributor in writing of such claim, and b) allow the -Commercial Contributor to control, and cooperate with the Commercial -Contributor in, the defense and any related settlement negotiations. The -Indemnified Contributor may participate in any such claim at its own -expense. - -For example, a Contributor might include the Program in a commercial -product offering, Product X. That Contributor is then a Commercial -Contributor. If that Commercial Contributor then makes performance -claims, or offers warranties related to Product X, those performance -claims and warranties are such Commercial Contributor's responsibility -alone. Under this section, the Commercial Contributor would have to -defend claims against the other Contributors related to those -performance claims and warranties, and if a court requires any other -Contributor to pay any damages as a result, the Commercial Contributor -must pay those damages. - -5. NO WARRANTY - -EXCEPT AS EXPRESSLY SET FORTH IN THIS AGREEMENT, THE PROGRAM IS -PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS -OF ANY KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, -ANY WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY -OR FITNESS FOR A PARTICULAR PURPOSE. Each Recipient is solely -responsible for determining the appropriateness of using and -distributing the Program and assumes all risks associated with its -exercise of rights under this Agreement , including but not limited to -the risks and costs of program errors, compliance with applicable laws, -damage to or loss of data, programs or equipment, and unavailability or -interruption of operations. - -6. DISCLAIMER OF LIABILITY - -EXCEPT AS EXPRESSLY SET FORTH IN THIS AGREEMENT, NEITHER RECIPIENT -NOR ANY CONTRIBUTORS SHALL HAVE ANY LIABILITY FOR ANY DIRECT, INDIRECT, -INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING -WITHOUT LIMITATION LOST PROFITS), 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 OR -DISTRIBUTION OF THE PROGRAM OR THE EXERCISE OF ANY RIGHTS GRANTED -HEREUNDER, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGES. - -7. GENERAL - -If any provision of this Agreement is invalid or unenforceable under -applicable law, it shall not affect the validity or enforceability of -the remainder of the terms of this Agreement, and without further action -by the parties hereto, such provision shall be reformed to the minimum -extent necessary to make such provision valid and enforceable. - -If Recipient institutes patent litigation against any entity -(including a cross-claim or counterclaim in a lawsuit) alleging that the -Program itself (excluding combinations of the Program with other -software or hardware) infringes such Recipient's patent(s), then such -Recipient's rights granted under Section 2(b) shall terminate as of the -date such litigation is filed. - -All Recipient's rights under this Agreement shall terminate if it -fails to comply with any of the material terms or conditions of this -Agreement and does not cure such failure in a reasonable period of time -after becoming aware of such noncompliance. If all Recipient's rights -under this Agreement terminate, Recipient agrees to cease use and -distribution of the Program as soon as reasonably practicable. However, -Recipient's obligations under this Agreement and any licenses granted by -Recipient relating to the Program shall continue and survive. - -Everyone is permitted to copy and distribute copies of this -Agreement, but in order to avoid inconsistency the Agreement is -copyrighted and may only be modified in the following manner. The -Agreement Steward reserves the right to publish new versions (including -revisions) of this Agreement from time to time. No one other than the -Agreement Steward has the right to modify this Agreement. The Eclipse -Foundation is the initial Agreement Steward. The Eclipse Foundation may -assign the responsibility to serve as the Agreement Steward to a -suitable separate entity. Each new version of the Agreement will be -given a distinguishing version number. The Program (including -Contributions) may always be distributed subject to the version of the -Agreement under which it was received. In addition, after a new version -of the Agreement is published, Contributor may elect to distribute the -Program (including its Contributions) under the new version. Except as -expressly stated in Sections 2(a) and 2(b) above, Recipient receives no -rights or licenses to the intellectual property of any Contributor under -this Agreement, whether expressly, by implication, estoppel or -otherwise. All rights in the Program not expressly granted under this -Agreement are reserved. - -This Agreement is governed by the laws of the State of New York and -the intellectual property laws of the United States of America. No party -to this Agreement will bring a legal action under this Agreement more -than one year after the cause of action arose. Each party waives its -rights to a jury trial in any resulting litigation. \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/evaluator.hpp b/ct_core/include/ct/external/cppad/cg/evaluator.hpp deleted file mode 100644 index a66fc314c..000000000 --- a/ct_core/include/ct/external/cppad/cg/evaluator.hpp +++ /dev/null @@ -1,627 +0,0 @@ -#ifndef CPPAD_CG_EVALUATOR_INCLUDED -#define CPPAD_CG_EVALUATOR_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -// forward declarations -template -class EvaluatorOperations; - -template -class EvaluatorBase; - -/** - * A base class for evaluators. - * Operation implementations (sin(), cos(), ...) should be implemented in a - * subclass of type FinalEvaluatorType. - * This allows static polymorphism through curiously recurring template - * pattern (CRTP). Therefore the default behaviour can be overridden without - * the use of virtual methods. - * - * Evaluators allow to reprocess operations defined in an operation graph - * for a different set of independent variables and (possibly) data types. - * This class should not be instantiated directly. - * - * @todo implement nonrecursive algorithm (so that there will never be any stack limit issues) - */ -template -class EvaluatorBase { - friend FinalEvaluatorType; -protected: - typedef typename CodeHandler::SourceCodePath SourceCodePath; -protected: - CodeHandler& handler_; - const ActiveOut* indep_; - CodeHandlerVector evals_; - std::map* > evalsArrays_; - bool underEval_; - size_t depth_; - SourceCodePath path_; -public: - - /** - * @param handler The source code handler - */ - inline EvaluatorBase(CodeHandler& handler) : - handler_(handler), - indep_(nullptr), - evals_(handler), - underEval_(false), - depth_(0) { // not really required (but it avoids warnings) - } - - /** - * @return true if this Evaluator is currently being used. - */ - inline bool isUnderEvaluation() { - return underEval_; - } - - /** - * Performs all the operations required to calculate the dependent - * variables with a (potentially) new data type - * - * @param indepNew The new independent variables. - * @param depOld Dependent variable vector (all variables must belong to - * the same code handler) - * @return The dependent variable values - * @throws CGException on error (such as an unhandled operation type) - */ - inline std::vector evaluate(const std::vector& indepNew, - const std::vector >& depOld) { - std::vector depNew(depOld.size()); - - evaluate(indepNew.data(), indepNew.size(), depNew.data(), depOld.data(), depNew.size()); - - return depNew; - } - - /** - * Performs all the operations required to calculate the dependent - * variables with a (potentially) new data type - * - * @param indepNew The new independent variables. - * @param indepSize The size of the array of independent variables. - * @param depNew The new dependent variable vector that will be created. - * @param depOld Dependent variable vector (all variables must belong to - * the same code handler) - * @param depSize The size of the array of dependent variables. - * @throws CGException on error (such as an unhandled operation type) - */ - inline void evaluate(const ActiveOut* indepNew, - size_t indepSize, - ActiveOut* depNew, - const CG* depOld, - size_t depSize) { - if (handler_.getIndependentVariableSize() != indepSize) { - throw CGException("Invalid independent variable size. Expected ", handler_.getIndependentVariableSize(), " but got ", indepSize, "."); - } - - CPPADCG_ASSERT_KNOWN(handler_.getIndependentVariableSize() == indepSize, "Invalid size the array of independent variables"); - - if (underEval_) { - throw CGException("The same evaluator cannot be used for simultaneous evaluations. " - "Either use a new one or wait for this one to finish its current evaluation."); - } - - underEval_ = true; - - clear(); // clean-up from any previous call that might have failed - evals_.fill(nullptr); - evals_.adjustSize(); - - depth_ = 0; - path_.clear(); - - if(path_.capacity() == 0) { - path_.reserve(30); - } - - try { - - indep_ = indepNew; - - for (size_t i = 0; i < depSize; i++) { - CPPADCG_ASSERT_UNKNOWN(depth_ == 0); - depNew[i] = evalCG(depOld[i]); - } - - clear(); // clean-up - - } catch (...) { - underEval_ = false; - throw; - } - - underEval_ = false; - } - - inline virtual ~EvaluatorBase() { - clear(); - } - -protected: - - /** - * clean-up - */ - inline void clear() { - for (const ActiveOut* it : evals_) { - delete it; - } - evals_.clear(); - - for (const auto& p : evalsArrays_) { - delete p.second; - } - evalsArrays_.clear(); - } - - inline ActiveOut evalCG(const CG& dep) { - if (dep.isParameter()) { - // parameter - return ActiveOut(dep.getValue()); - } else { - return evalOperations(*dep.getOperationNode()); - } - } - - inline ActiveOut evalArg(const std::vector >& args, - size_t pos) { - return evalArg(args[pos], pos); - } - - inline ActiveOut evalArg(const Argument& arg, - size_t pos) { - if (arg.getOperation() != nullptr) { - path_.back().argIndex = pos; - ActiveOut a = evalOperations(*arg.getOperation()); - return a; - } else { - // parameter - return ActiveOut(*arg.getParameter()); - } - } - - inline const ActiveOut& evalOperations(OperationNode& node) { - CPPADCG_ASSERT_KNOWN(node.getHandlerPosition() < handler_.getManagedNodesCount(), "this node is not managed by the code handler"); - - // check if this node was previously determined - if (evals_[node] != nullptr) { - return *evals_[node]; - } - - // first evaluation of this node - FinalEvaluatorType& thisOps = static_cast(*this); - - path_.push_back(OperationPathNode(&node, -1)); - depth_++; - - ActiveOut result = thisOps.evalOperation(node); - - // save it for reuse - CPPADCG_ASSERT_UNKNOWN(evals_[node] == nullptr); - ActiveOut* resultPtr = new ActiveOut(result); - evals_[node] = resultPtr; - - thisOps.processActiveOut(node, *resultPtr); - - depth_--; - path_.pop_back(); - - return *resultPtr; - } - - inline std::vector& evalArrayCreationOperation(OperationNode& node) { - - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::ArrayCreation, "Invalid array creation operation"); - CPPADCG_ASSERT_KNOWN(node.getHandlerPosition() < handler_.getManagedNodesCount(), "this node is not managed by the code handler"); - - // check if this node was previously determined - auto it = evalsArrays_.find(node.getHandlerPosition()); - if (it != evalsArrays_.end()) { - return *it->second; - } - - const std::vector >& args = node.getArguments(); - std::vector* resultArray = new std::vector(args.size()); - - // save it for reuse - evalsArrays_[node.getHandlerPosition()] = resultArray; - - // define its elements - for (size_t a = 0; a < args.size(); a++) { - (*resultArray)[a] = evalArg(args, a); - } - - return *resultArray; - } - -}; - - -/** - * Defines the default operations for evaluators. - * Evaluators allow to reprocess operations defined in an operation graph - * for a different set of independent variables and (possibly) data types. - * - * This allows static polymorphism through curiously recurring template - * pattern (CRTP). Therefore the default behaviour can be overridden without - * the use of virtual methods. - * This class should not be instantiated directly. - */ -template -class EvaluatorOperations : public EvaluatorBase { - /** - * must be friends with its super classes since there can be a cast to - * this type due to the curiously recurring template pattern (CRTP) - */ - friend class EvaluatorBase; -public: - typedef EvaluatorBase Base; - typedef OperationNode NodeIn; - typedef Argument ArgIn; -public: - inline EvaluatorOperations(CodeHandler& handler): - Base(handler) { - } - - virtual ~EvaluatorOperations() { } - -protected: - - using Base::evalArg; - - /** - * Clones a node with the new type. - * Override this method to add a custom node generation behaviour which - * does not follow the original operation graph. - * - * @param node the original node - * @return the clone of the original node - */ - inline ActiveOut evalOperation(OperationNode& node) { - FinalEvaluatorType& thisOps = static_cast(*this); - - const CGOpCode code = node.getOperationType(); - switch (code) { - case CGOpCode::Assign: - return thisOps.evalAssign(node); - - case CGOpCode::Abs: // abs(variable) - return thisOps.evalAbs(node); - - case CGOpCode::Acos: // acos(variable) - return thisOps.evalAcos(node); - - case CGOpCode::Add: // a + b - return thisOps.evalAdd(node); - - case CGOpCode::Alias: - return thisOps.evalAlias(node); - - //case CGArrayCreationOp: // {a, b, c ...} - case CGOpCode::ArrayElement: // x[i] - return thisOps.evalArrayElement(node); - - case CGOpCode::Asin: // asin(variable) - return thisOps.evalAsin(node); - - case CGOpCode::Atan: // atan(variable) - return thisOps.evalAtan(node); - - //CGAtomicForwardOp - //CGAtomicReverseOp - case CGOpCode::ComLt: // return left < right? trueCase: falseCase - return thisOps.evalCompareLt(node); - - case CGOpCode::ComLe: // return left <= right? trueCase: falseCase - return thisOps.evalCompareLe(node); - - case CGOpCode::ComEq: // return left == right? trueCase: falseCase - return thisOps.evalCompareEq(node); - - case CGOpCode::ComGe: // return left >= right? trueCase: falseCase - return thisOps.evalCompareGe(node); - - case CGOpCode::ComGt: // return left > right? trueCase: falseCase - return thisOps.evalCompareGt(node); - - case CGOpCode::ComNe: // return left != right? trueCase: falseCase - return thisOps.evalCompareNe(node); - - case CGOpCode::Cosh: // cosh(variable) - return thisOps.evalCosh(node); - - case CGOpCode::Cos: // cos(variable) - return thisOps.evalCos(node); - - case CGOpCode::Div: // a / b - return thisOps.evalDiv(node); - - case CGOpCode::Exp: // exp(variable) - return thisOps.evalExp(node); - - case CGOpCode::Inv: // independent variable - return thisOps.evalIndependent(node); - - case CGOpCode::Log: // log(variable) - return thisOps.evalLog(node); - - case CGOpCode::Mul: // a * b - return thisOps.evalMul(node); - - case CGOpCode::Pow: // pow(a, b) - return thisOps.evalPow(node); - - //case PriOp: // PrintFor(text, parameter or variable, parameter or variable) - case CGOpCode::Sign: // return (x > 0)? 1.0:((x == 0)? 0.0:-1) - return thisOps.evalSign(node); - - case CGOpCode::Sinh: // sinh(variable) - return thisOps.evalSinh(node); - - case CGOpCode::Sin: // sin(variable) - return thisOps.evalSin(node); - - case CGOpCode::Sqrt: // sqrt(variable) - return thisOps.evalSqrt(node); - - case CGOpCode::Sub: // a - b - return thisOps.evalSub(node); - - case CGOpCode::Tanh: // tanh(variable) - return thisOps.evalTanh(node); - - case CGOpCode::Tan: // tan(variable) - return thisOps.evalTan(node); - - case CGOpCode::UnMinus: // -(a) - return thisOps.evalMinus(node); - - default: - return thisOps.evalUnsupportedOperation(node); - } - } - - inline ActiveOut evalAssign(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for assign()"); - return evalArg(args, 0); - } - - inline ActiveOut evalAbs(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for abs()"); - return abs(evalArg(args, 0)); - } - - inline ActiveOut evalAcos(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for acos()"); - return acos(evalArg(args, 0)); - } - - inline ActiveOut evalAdd(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 2, "Invalid number of arguments for addition"); - return evalArg(args, 0) + evalArg(args, 1); - } - - inline ActiveOut evalAlias(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for alias"); - return evalArg(args, 0); - } - - inline ActiveOut evalArrayElement(const NodeIn& node) { - const std::vector& args = node.getArguments(); - const std::vector& info = node.getInfo(); - CPPADCG_ASSERT_KNOWN(args.size() == 2, "Invalid number of arguments for array element"); - CPPADCG_ASSERT_KNOWN(args[0].getOperation() != nullptr, "Invalid argument for array element"); - CPPADCG_ASSERT_KNOWN(args[1].getOperation() != nullptr, "Invalid argument for array element"); - CPPADCG_ASSERT_KNOWN(info.size() == 1, "Invalid number of information data for array element"); - size_t index = info[0]; - std::vector& array = this->evalArrayCreationOperation(*args[0].getOperation()); // array creation - - FinalEvaluatorType& thisOps = static_cast(*this); - thisOps.evalAtomicOperation(*args[1].getOperation()); // atomic operation - - return array[index]; - } - - inline ActiveOut evalAsin(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for asin()"); - return asin(evalArg(args, 0)); - } - - inline ActiveOut evalAtan(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for atan()"); - return atan(evalArg(args, 0)); - } - - inline ActiveOut evalCompareLt(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 4, "Invalid number of arguments for CondExpOp(CompareLt, )"); - return CondExpOp(CompareLt, evalArg(args, 0), evalArg(args, 1), evalArg(args, 2), evalArg(args, 3)); - } - - inline ActiveOut evalCompareLe(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 4, "Invalid number of arguments for CondExpOp(CompareLe, )"); - return CondExpOp(CompareLe, evalArg(args, 0), evalArg(args, 1), evalArg(args, 2), evalArg(args, 3)); - } - - inline ActiveOut evalCompareEq(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 4, "Invalid number of arguments for CondExpOp(CompareEq, )"); - return CondExpOp(CompareEq, evalArg(args, 0), evalArg(args, 1), evalArg(args, 2), evalArg(args, 3)); - } - - inline ActiveOut evalCompareGe(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 4, "Invalid number of arguments for CondExpOp(CompareGe, )"); - return CondExpOp(CompareGe, evalArg(args, 0), evalArg(args, 1), evalArg(args, 2), evalArg(args, 3)); - } - - inline ActiveOut evalCompareGt(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 4, "Invalid number of arguments for CondExpOp(CompareGt, )"); - return CondExpOp(CompareGt, evalArg(args, 0), evalArg(args, 1), evalArg(args, 2), evalArg(args, 3)); - } - - inline ActiveOut evalCompareNe(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 4, "Invalid number of arguments for CondExpOp(CompareNe, )"); - return CondExpOp(CompareNe, evalArg(args, 0), evalArg(args, 1), evalArg(args, 2), evalArg(args, 3)); - } - - inline ActiveOut evalCosh(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for cosh()"); - return cosh(evalArg(args, 0)); - } - - inline ActiveOut evalCos(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for cos()"); - return cos(evalArg(args, 0)); - } - - inline ActiveOut evalDiv(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 2, "Invalid number of arguments for division"); - return evalArg(args, 0) / evalArg(args, 1); - } - - inline ActiveOut evalExp(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for exp()"); - return exp(evalArg(args, 0)); - } - - inline ActiveOut evalIndependent(const NodeIn& node) { - size_t index = this->handler_.getIndependentVariableIndex(node); - return this->indep_[index]; - } - - inline ActiveOut evalLog(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for log()"); - return log(evalArg(args, 0)); - } - - inline ActiveOut evalMul(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 2, "Invalid number of arguments for multiplication"); - return evalArg(args, 0) * evalArg(args, 1); - } - - inline ActiveOut evalPow(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 2, "Invalid number of arguments for pow()"); - return pow(evalArg(args, 0), evalArg(args, 1)); - - } - - //case PriOp: // PrintFor(text, parameter or variable, parameter or variable) - inline ActiveOut evalSign(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for sign()"); - return sign(evalArg(args, 0)); - } - - inline ActiveOut evalSinh(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for sinh()"); - return sinh(evalArg(args, 0)); - } - - inline ActiveOut evalSin(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for sin()"); - return sin(evalArg(args, 0)); - } - - inline ActiveOut evalSqrt(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for sqrt()"); - return sqrt(evalArg(args, 0)); - } - - inline ActiveOut evalSub(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 2, "Invalid number of arguments for subtraction"); - return evalArg(args, 0) - evalArg(args, 1); - } - - inline ActiveOut evalTanh(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for tanh()"); - return tanh(evalArg(args, 0)); - } - - inline ActiveOut evalTan(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for tan()"); - return tan(evalArg(args, 0)); - } - - inline ActiveOut evalMinus(const NodeIn& node) { - const std::vector& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 1, "Invalid number of arguments for unary minus"); - return -evalArg(args, 0); - } - - inline ActiveOut evalUnsupportedOperation(const NodeIn& node) { - throw CGException("Unknown operation code '", node.getOperationType(), "'"); - } - - inline void evalAtomicOperation(const NodeIn& node) { - throw CGException("Evaluator is unable to handle atomic functions for these variable types"); - } - - inline void processActiveOut(const NodeIn& node, - ActiveOut& a) { - } -}; - -/** - * An evaluator allows to reprocess operations defined in an operation graph - * for a different set of independent variables and (possibly) data types. - */ -template > -class Evaluator : public EvaluatorOperations > { -public: - typedef EvaluatorOperations > Base; -public: - - inline Evaluator(CodeHandler& handler) : - Base(handler) { - } - - inline virtual ~Evaluator() { - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/evaluator_ad.hpp b/ct_core/include/ct/external/cppad/cg/evaluator_ad.hpp deleted file mode 100644 index 45744a844..000000000 --- a/ct_core/include/ct/external/cppad/cg/evaluator_ad.hpp +++ /dev/null @@ -1,147 +0,0 @@ -#ifndef CPPAD_CG_EVALUATOR_AD_INCLUDED -#define CPPAD_CG_EVALUATOR_AD_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Helper class for the specialization of Evaluator for an output active type of AD<> - * This class should not be instantiated directly. - */ -template -class EvaluatorAD : public EvaluatorOperations, FinalEvaluatorType > { - /** - * must be friends with one of its super classes since there is a cast to - * this type due to the curiously recurring template pattern (CRTP) - */ - friend EvaluatorOperations, FinalEvaluatorType>; -public: - typedef CppAD::AD ActiveOut; - typedef EvaluatorOperations, FinalEvaluatorType> Super; -protected: - using Super::handler_; - using Super::evalArrayCreationOperation; -protected: - std::set*> evalsAtomic_; - std::map* > atomicFunctions_; -public: - - inline EvaluatorAD(CodeHandler& handler) : - Super(handler) { - } - - inline virtual ~EvaluatorAD() { - } - - /** - * Provides an atomic function. - * - * @param id The atomic function ID - * @param atomic The atomic function - * @return True if an atomic function with the same ID was already - * defined, false otherwise. - */ - virtual bool addAtomicFunction(size_t id, atomic_base& atomic) { - bool exists = atomicFunctions_.find(id) != atomicFunctions_.end(); - atomicFunctions_[id] = &atomic; - return exists; - } - - virtual void addAtomicFunctions(const std::map* >& atomics) { - for (const auto& it : atomics) { - atomic_base* atomic = it.second; - if (atomic != nullptr) { - atomicFunctions_[it.first] = atomic; - } - } - } - -protected: - - /** - * @throws CGException on an internal evaluation error - * - * @note overrides the default evalAtomicOperation() even though this - * method is not virtual (hides a method in EvaluatorOperations) - */ - inline void evalAtomicOperation(OperationNode& node) { - - if (evalsAtomic_.find(&node) != evalsAtomic_.end()) { - return; - } - - if (node.getOperationType() != CGOpCode::AtomicForward) { - throw CGException("Evaluator can only handle zero forward mode for atomic functions"); - } - - const std::vector& info = node.getInfo(); - const std::vector >& args = node.getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() == 2, "Invalid number of arguments for atomic forward mode"); - CPPADCG_ASSERT_KNOWN(info.size() == 3, "Invalid number of information data for atomic forward mode"); - - // find the atomic function - size_t id = info[0]; - typename std::map* >::const_iterator itaf = atomicFunctions_.find(id); - atomic_base* atomicFunction = nullptr; - if (itaf != atomicFunctions_.end()) { - atomicFunction = itaf->second; - } - - if (atomicFunction == nullptr) { - std::stringstream ss; - ss << "No atomic function defined in the evaluator for "; - const std::string* atomName = handler_.getAtomicFunctionName(id); - if (atomName != nullptr) { - ss << "'" << *atomName << "'"; - } else - ss << "id '" << id << "'"; - throw CGException(ss.str()); - } - - size_t p = info[2]; - if (p != 0) { - throw CGException("Evaluator can only handle zero forward mode for atomic functions"); - } - const std::vector& ax = evalArrayCreationOperation(*args[0].getOperation()); - std::vector& ay = evalArrayCreationOperation(*args[1].getOperation()); - - (*atomicFunction)(ax, ay); - - evalsAtomic_.insert(&node); - } -}; - -/** - * Specialization of Evaluator for an output active type of AD<> - */ -template -class Evaluator > : public EvaluatorAD > > { -public: - typedef CppAD::AD ActiveOut; - typedef EvaluatorAD > > Super; -public: - - inline Evaluator(CodeHandler& handler) : - Super(handler) { - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/evaluator_adcg.hpp b/ct_core/include/ct/external/cppad/cg/evaluator_adcg.hpp deleted file mode 100644 index 177e0cc55..000000000 --- a/ct_core/include/ct/external/cppad/cg/evaluator_adcg.hpp +++ /dev/null @@ -1,126 +0,0 @@ -#ifndef CPPAD_CG_EVALUATOR_ADCG_INCLUDED -#define CPPAD_CG_EVALUATOR_ADCG_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Specialization for an output active type of AD> - */ -template -class Evaluator, CppAD::AD > > : public EvaluatorAD, Evaluator, CppAD::AD > > > { - /** - * must be friends with one of its super classes since there is a cast to - * this type due to the curiously recurring template pattern (CRTP) - */ - friend EvaluatorBase, CppAD::AD >, Evaluator, CppAD::AD > > >; -public: - typedef CG ScalarOut; - typedef CppAD::AD ActiveOut; - typedef EvaluatorAD, CppAD::AD > > > Super; -protected: - using Super::evalsAtomic_; - using Super::atomicFunctions_; - using Super::handler_; - using Super::evalArrayCreationOperation; -protected: - /** - * Whenever set to true it will add a CppAD::PrintFor(0, "", var, name) - * to every variable with a name so that names can be recovered using - * a OperationNodeNameStreambuf. - */ - bool printFor_; - /** - * Whenever set to true it will copy the name in original operation - * nodes into new operation nodes created in AD. - */ - bool adcgName_; -public: - - inline Evaluator(CodeHandler& handler) : - Super(handler), - printFor_(false), - adcgName_(true) { - } - - inline virtual ~Evaluator() { - } - - /** - * Whenever set to true it will add a CppAD::PrintFor(0, "", var, name) - * to every variable with a name so that names can be recovered using - * a OperationNodeNameStreambuf. - */ - inline void setPrintFor(bool printFor) { - printFor_ = printFor; - } - - /** - * true if a CppAD::PrintFor(0, "", var, name) will be added - * to every variable with a name so that names can be recovered using - * a OperationNodeNameStreambuf. - * The default value is false. - */ - inline bool isPrintFor() const { - return printFor_; - } - - /** - * Whenever set to true it will copy the name in original operation - * nodes into new operation nodes created in AD. - */ - inline void setCopyAdCgName(bool adcgName) { - adcgName_ = adcgName; - } - - /** - * Whenever set to true it will copy the name in original operation - * nodes into new operation nodes created in AD. - * The default value is true. - */ - inline bool isCopyAdCgName() const { - return adcgName_; - } - -protected: - - /** - * @note overrides the default processActiveOut() even though this method - * is not virtual (hides a method in EvaluatorOperations) - */ - void processActiveOut(const OperationNode& node, - ActiveOut& a) { - if (node.getName() != nullptr) { - if(adcgName_ && CppAD::Variable(a)) { - ScalarOut a2(CppAD::Value(CppAD::Var2Par(a))); - if (a2.getOperationNode() != nullptr) { - a2.getOperationNode()->setName(*node.getName()); - } - } - - if(printFor_) { - CppAD::PrintFor(ActiveOut(0), "", a, node.getName()->c_str()); - } - } - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/evaluator_adolc.hpp b/ct_core/include/ct/external/cppad/cg/evaluator_adolc.hpp deleted file mode 100644 index d8906e95b..000000000 --- a/ct_core/include/ct/external/cppad/cg/evaluator_adolc.hpp +++ /dev/null @@ -1,116 +0,0 @@ -#ifndef CPPAD_CG_EVALUATOR_ADOLC_INCLUDED -#define CPPAD_CG_EVALUATOR_ADOLC_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include -#include - -/** - * defined required functions for adoubles - */ -inline adouble abs(const adouble& val) { - return fabs(val); -} - -inline adouble sign(const adouble& val) { - throw CppAD::cg::CGException("Sign operation not implemented in ADOL-C"); - //adouble temp; - //condassign(temp, val, adouble(1.0), adouble(-1.0)); // warning it should return zero if val == 0 but there is no way to do this in Adol-C - //return temp; -} - -inline adouble condExpLt(const adouble& left, const adouble& right, - const adouble& exp_if_true, const adouble& exp_if_false) { - adouble temp; - condassign(temp, right - left, exp_if_true, exp_if_false); // temp = (right - left>0)? exp_if_true: exp_if_false - return temp; -} - -inline adouble condExpLe(const adouble& left, const adouble& right, const adouble& exp_if_true, const adouble& exp_if_false) { - throw CppAD::cg::CGException("Conditional operation (<=) not implemented in ADOL-C"); -} - -inline adouble condExpEq(const adouble& left, const adouble& right, - const adouble& exp_if_true, const adouble& exp_if_false) { - throw CppAD::cg::CGException("Conditional operation (==) not implemented in ADOL-C"); -} - -inline adouble condExpGe(const adouble& left, const adouble& right, - const adouble& exp_if_true, const adouble& exp_if_false) { - throw CppAD::cg::CGException("Conditional operation (>=) not implemented in ADOL-C"); -} - -inline adouble condExpGt(const adouble& left, const adouble& right, - const adouble& exp_if_true, const adouble& exp_if_false) { - adouble temp; - condassign(temp, left - right, exp_if_true, exp_if_false); - return temp; -} - -inline adouble condExpNe(const adouble& left, const adouble& right, - const adouble& exp_if_true, const adouble& exp_if_false) { - throw CppAD::cg::CGException("Conditional operation (!=) not implemented in ADOL-C"); -} - -inline adouble CondExpOp(enum CppAD::CompareOp cop, - const adouble& left, - const adouble& right, - const adouble& trueCase, - const adouble& falseCase) { - switch (cop) { - case CppAD::CompareLt: // less than - return condExpLt(left, right, trueCase, falseCase); - case CppAD::CompareLe: // less than or equal - return condExpLe(left, right, trueCase, falseCase); - case CppAD::CompareEq: // equal - return condExpEq(left, right, trueCase, falseCase); - case CppAD::CompareGe: // greater than or equal - return condExpGe(left, right, trueCase, falseCase); - case CppAD::CompareGt: // greater than - return condExpGt(left, right, trueCase, falseCase); - case CppAD::CompareNe: - return condExpNe(left, right, trueCase, falseCase); - default: - throw CppAD::cg::CGException("Unknown comparison type"); - } -} - -namespace CppAD { -namespace cg { - -/** - * Evaluator specialization for Adol-C - */ -template -class Evaluator : public EvaluatorOperations > { -public: - typedef adouble ActiveOut; - typedef EvaluatorOperations > Super; -public: - - inline Evaluator(CodeHandler& handler) : - Super(handler) { - } - - inline virtual ~Evaluator() { - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/evaluator_cg.hpp b/ct_core/include/ct/external/cppad/cg/evaluator_cg.hpp deleted file mode 100644 index a06b15114..000000000 --- a/ct_core/include/ct/external/cppad/cg/evaluator_cg.hpp +++ /dev/null @@ -1,76 +0,0 @@ -#ifndef CPPAD_CG_EVALUATOR_CG_INCLUDED -#define CPPAD_CG_EVALUATOR_CG_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Used for the specialization of Evaluator for an output active type of CG. - * This class should not be instantiated directly. - */ -template -class EvaluatorCG : public EvaluatorOperations, FinalEvaluatorType> { - /** - * must be friends with one of its super classes since there is a cast to - * this type due to the curiously recurring template pattern (CRTP) - */ - friend EvaluatorBase, FinalEvaluatorType>; -public: - typedef CG ActiveOut; -protected: - typedef EvaluatorOperations, FinalEvaluatorType> Super; -public: - - inline EvaluatorCG(CodeHandler& handler) : - Super(handler) { - } - -protected: - - /** - * @note overrides the default processActiveOut() even though this method - * is not virtual (hides a method in EvaluatorOperations) - */ - void processActiveOut(const OperationNode& node, - ActiveOut& a) { - if (node.getName() != nullptr) { - if (a.getOperationNode() != nullptr) { - a.getOperationNode()->setName(*node.getName()); - } - } - } - -}; - -/** - * Specialization of Evaluator for an output active type of CG - */ -template -class Evaluator > : public EvaluatorCG > > { -protected: - typedef EvaluatorCG > > Super; -public: - - inline Evaluator(CodeHandler& handler) : - Super(handler) { - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/evaluator_solve.hpp b/ct_core/include/ct/external/cppad/cg/evaluator_solve.hpp deleted file mode 100644 index ad8f36ee7..000000000 --- a/ct_core/include/ct/external/cppad/cg/evaluator_solve.hpp +++ /dev/null @@ -1,217 +0,0 @@ -#ifndef CPPAD_CG_EVALUATOR_SOLVE_INCLUDED -#define CPPAD_CG_EVALUATOR_SOLVE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Specialization of EvaluatorCG which can replace some operations. - * It only clones some of the nodes. - * It is used by the symbolic solver. - */ -template -class EvaluatorCloneSolve : public EvaluatorCG> { - /** - * must be friends with one of its super classes since there is a cast to - * this type due to the curiously recurring template pattern (CRTP) - */ - typedef EvaluatorCloneSolve FinalEvaluatorType; - friend EvaluatorBase, FinalEvaluatorType>; -public: - typedef CG ActiveOut; - typedef typename CodeHandler::SourceCodePath SourceCodePath; -protected: - typedef EvaluatorCG Super; -private: - /** - * the operation paths which should be cloned or replaced with values in - * replacement_ - */ - const std::vector* paths_; - /** - * replacements for the operations along the paths - * (a null means that the original should be cloned) - */ - const std::vector*>*>* replaceOnPath_; - /** - * the operation paths which should be cloned or replaced with values in - * replaceOnGraph_ - */ - const BidirGraph* pathGraph_; - /** - * replacements for the operations along the paths - */ - const std::map*, CG>* replaceOnGraph_; - /** - * operations which should be cloned - */ - const std::set*>* clone_; - /** - * replacements for the operations along the paths - */ - const std::map, CG>* replaceArgument_; -public: - - /** - * Creates a new evaluator. - * - * @param handler - * @param paths operation nodes in a path which should be cloned - * (there shouldn't be multiple usages of these nodes) - * @param replaceOnPath replacements for the operations along the paths - * (a null means that the original should be cloned) - */ - inline EvaluatorCloneSolve(CodeHandler& handler, - const std::vector& paths, - const std::vector*>*>& replaceOnPath) : - Super(handler), - paths_(&paths), - replaceOnPath_(&replaceOnPath), - pathGraph_(nullptr), - replaceOnGraph_(nullptr), - clone_(nullptr), - replaceArgument_(nullptr) { - CPPADCG_ASSERT_UNKNOWN(paths_->size() == replaceOnPath_->size()); -#ifndef NDEBUG - for (size_t i = 0; i < paths.size(); ++i) { - CPPADCG_ASSERT_UNKNOWN(paths[i]->size() == replaceOnPath[i]->size()); - } -#endif - } - - /** - * Creates a new evaluator. - * - * @param handler - * @param pathGraph the operation paths which should be cloned - * @param replaceOnGraph replacements for the operations along the graph - */ - inline EvaluatorCloneSolve(CodeHandler& handler, - const BidirGraph& pathGraph, - const std::map*, CG >& replaceOnGraph) : - Super(handler), - paths_(nullptr), - replaceOnPath_(nullptr), - pathGraph_(&pathGraph), - replaceOnGraph_(&replaceOnGraph), - clone_(nullptr), - replaceArgument_(nullptr) { - } - - /** - * Creates a new evaluator. - * - * @param handler - * @param clone operations which should be cloned - * @param replaceArgument replacements for the operations along the paths - */ - inline EvaluatorCloneSolve(CodeHandler& handler, - const std::set*>& clone, - const std::map, CG>& replaceArgument) : - Super(handler), - paths_(nullptr), - replaceOnPath_(nullptr), - pathGraph_(nullptr), - replaceOnGraph_(nullptr), - clone_(&clone), - replaceArgument_(&replaceArgument) { - } - -protected: - - /** - * @note overrides the default evalOperation() even though this method - * is not virtual (hides a method in EvaluatorOperations) - */ - inline ActiveOut evalOperation(OperationNode& node) { - CPPADCG_ASSERT_UNKNOWN(this->depth_ > 0); - - if(paths_ != nullptr) { - const auto& paths = *paths_; - for (size_t i = 0; i < paths.size(); ++i) { - size_t d = this->depth_ - 1; - if (isOnPath(*paths[i])) { - // in one of the paths - - auto* r = (*(*replaceOnPath_)[i])[d]; - if (r != nullptr) { - return *r; - } else { - return Super::evalOperation(node); - } - } - } - } - - if(pathGraph_ != nullptr) { - const PathNodeEdges* egdes = pathGraph_->find(node); - if (egdes != nullptr) { - auto it = replaceOnGraph_->find(egdes); - if (it != replaceOnGraph_->end()) { - return it->second; - } else { - return Super::evalOperation(node); - } - } - } - - if (clone_ != nullptr) { - if (clone_->find(&node) != clone_->end()) { - return Super::evalOperation(node); - } - } - - if (replaceArgument_ != nullptr) { - size_t d = this->depth_ - 1; - if (d > 0) { - auto it = replaceArgument_->find(this->path_[d - 1]); - if (it != replaceArgument_->end()) { - return it->second; - } - } - } - - return CG(node); // use original - } - -private: - inline bool isOnPath(const SourceCodePath& path) const { - size_t d = this->depth_ - 1; - - if (d >= path.size()) - return false; - - if (this->path_[d].node != path[d].node) // compare only the node - return false; - - if (d > 0) { - for (size_t j = 0; j < d; ++j) { - if (this->path_[j] != path[j]) { // compare node and argument index - return false; - } - } - } - - return true; - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/exception.hpp b/ct_core/include/ct/external/cppad/cg/exception.hpp deleted file mode 100644 index 0549f2497..000000000 --- a/ct_core/include/ct/external/cppad/cg/exception.hpp +++ /dev/null @@ -1,75 +0,0 @@ -#ifndef CPPAD_CG_EXCEPTION_INCLUDED -#define CPPAD_CG_EXCEPTION_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Source code generation exception - * - * @author Joao Leal - */ -class CGException : public std::exception { -protected: - std::string _message; - -public: - - inline CGException(const std::string& message) throw () : - _message(message) { - } - - template - explicit CGException(const Ts&... ts) throw () { - std::ostringstream s; - createMessage(s, ts...); - _message = s.str(); - } - - CGException() throw () = delete; - - const char* what() const throw () { - return _message.c_str(); - } - - virtual ~CGException() throw () { - } - -private: - - template - inline void createMessage(std::ostringstream& s, const T& t, const Ts&... ts) throw () { - s << t; - createMessage(s, ts...); - } - - template - inline void createMessage(std::ostringstream& s, const T& t) throw () { - s << t; - } - -}; - -inline std::ostream& operator<<(std::ostream& out, const CGException& rhs) { - out << rhs.what(); - return out; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/extra/declare_extra.hpp b/ct_core/include/ct/external/cppad/cg/extra/declare_extra.hpp deleted file mode 100644 index 7a78a2a61..000000000 --- a/ct_core/include/ct/external/cppad/cg/extra/declare_extra.hpp +++ /dev/null @@ -1,136 +0,0 @@ -#ifndef CPPAD_EXTRA_DECLARE_EXTRA_INCLUDED -#define CPPAD_EXTRA_DECLARE_EXTRA_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include -#include -#include - -// forward declarations -namespace CppAD { -namespace cg { - -/*********************************************************************** - * Combined Jacobian and Hessian evaluation - **********************************************************************/ - -class SparseForjacHessianWorkJac; -class SparseForjacHessianWorkHes; -class SparseForjacHessianWork; - -template -size_t sparseForJacHessian(ADFun& fun, - const VectorBase& x, - const VectorBase& w, - VectorBase& y, - const VectorSet& jac_p, - const VectorSize& jac_row, - const VectorSize& jac_col, - VectorBase& jac, - const VectorSet& hes_p, - const VectorSize& hes_row, - const VectorSize& hes_col, - VectorBase& hes, - SparseForjacHessianWork& work); - -template -size_t sparseForJacHessian(ADFun& fun, - const VectorBase& x, - const VectorVectorBase& w, - VectorBase& y, - const VectorSet& jac_p, - const VectorSize& jac_row, - const VectorSize& jac_col, - VectorBase& jac, - const VectorSet& hes_p, - const VectorSize& hes_row, - const VectorSize& hes_col, - VectorVectorBase& hes, - SparseForjacHessianWork& work); - -/*********************************************************************** - * Sparsity evaluation - **********************************************************************/ - -template -inline VectorBool jacobianForwardSparsity(ADFun& fun); - -template -inline VectorBool jacobianReverseSparsity(ADFun& fun); - -template -inline VectorSet jacobianForwardSparsitySet(ADFun& fun); - -template -inline VectorSet jacobianReverseSparsitySet(ADFun& fun); - -template -inline VectorBool jacobianSparsity(ADFun& fun); - -template -inline VectorSet jacobianSparsitySet(ADFun& fun); - -inline bool estimateBestJacobianADMode(const std::vector& jacRows, - const std::vector& jacCols); - -template -inline VectorBool hessianSparsity(ADFun& fun, - bool transpose = false); - -template -inline VectorSet hessianSparsitySet(ADFun& fun, - const std::set& w, - bool transpose = false); - -template -inline VectorSet hessianSparsitySet(ADFun& fun, - bool transpose = false); - -template -inline VectorBool hessianSparsity(ADFun& fun, - size_t i, - bool transpose = false); - -template -inline VectorSet hessianSparsitySet(ADFun& fun, - size_t i, - bool transpose = false); - -/*********************************************************************** - * Sparsity conversion - **********************************************************************/ - -template -inline void generateSparsityIndexes(const VectorBool& sparsity, - size_t m, - size_t n, - VectorSize& row, - VectorSize& col); - -template -inline void generateSparsityIndexes(const VectorSet& sparsity, - VectorSize& row, - VectorSize& col); - -template -inline void generateSparsitySet(const VectorSize& row, - const VectorSize& col, - VectorSet& sparsity); -} -} - -#endif - diff --git a/ct_core/include/ct/external/cppad/cg/extra/extra.hpp b/ct_core/include/ct/external/cppad/cg/extra/extra.hpp deleted file mode 100644 index f1a87c2af..000000000 --- a/ct_core/include/ct/external/cppad/cg/extra/extra.hpp +++ /dev/null @@ -1,23 +0,0 @@ -#ifndef CPPAD_EXTRA_EXTRA_INCLUDED -#define CPPAD_EXTRA_EXTRA_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include - -#include -#include - -#endif diff --git a/ct_core/include/ct/external/cppad/cg/extra/sparse_forjac_hessian.hpp b/ct_core/include/ct/external/cppad/cg/extra/sparse_forjac_hessian.hpp deleted file mode 100644 index e90afe4d7..000000000 --- a/ct_core/include/ct/external/cppad/cg/extra/sparse_forjac_hessian.hpp +++ /dev/null @@ -1,683 +0,0 @@ -#ifndef CPPAD_EXTRA_SPARSE_FORJAC_HESSIAN_INCLUDED -#define CPPAD_EXTRA_SPARSE_FORJAC_HESSIAN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ -/** - * Adapted from CppAD - */ -namespace CppAD { -namespace cg { - -/** - * class used by SparseForJacHessian to hold information relative to the - * Jacobian so it does not need to be recomputed. - */ -class SparseForjacHessianWorkJac { -public: - /// version of user row array with the extra value m at end - std::vector user_row; - /// version of user col array with the extra value n at end - std::vector user_col; - /// indices that sort the user arrays by row - /// with the extra value K at the end - std::vector sort_row; - /// indices that sort the user arrays by column - /// with the extra value K at the end - std::vector sort_col; - /// number elements in the user sparse Jacobian - size_t K; - - template - inline void prepare(const ADFun& fun, - const VectorSize& row, - const VectorSize& col) { - /** - * Code adapted from ADFun::SparseJacobianForward() - */ - K = row.size(); - size_t n = fun.Domain(); - size_t m = fun.Range(); - - if (user_row.size() == 0) { - // create version of (row, col, k) sorted by column value - user_col.resize(K + 1); - user_row.resize(K + 1); - sort_col.resize(K + 1); - - // put sorted indices in user_row and user_col - for (size_t k = 0; k < K; k++) { - user_row[k] = row[k]; - user_col[k] = col[k]; - } - user_row[K] = m; - user_col[K] = n; - - // put sorting indices in sort_col - index_sort(user_col, sort_col); - } - -#ifndef NDEBUG - CPPAD_ASSERT_KNOWN(size_t(row.size()) == K && size_t(col.size()) == K, - "sparseForJacHessian: either r or c does not have " - "the same size as jac."); - CPPAD_ASSERT_KNOWN(user_row.size() == K + 1 && - user_col.size() == K + 1 && - sort_col.size() == K + 1, - "sparseForJacHessian: invalid value in work."); - for (size_t k = 0; k < K; k++) { - CPPAD_ASSERT_KNOWN(row[k] < m, - "sparseForJacHessian: invalid value in r."); - CPPAD_ASSERT_KNOWN(col[k] < n, - "sparseForJacHessian: invalid value in c."); - CPPAD_ASSERT_KNOWN(sort_col[k] < K, - "sparseForJacHessian: invalid value in work."); - CPPAD_ASSERT_KNOWN(user_row[k] == row[k], - "sparseForJacHessian: invalid value in work."); - CPPAD_ASSERT_KNOWN(user_col[k] == col[k], - "sparseForJacHessian: invalid value in work."); - } -#endif - } - /// inform CppAD that this information needs to be recomputed - - inline void clear(void) { - user_row.clear(); - user_col.clear(); - sort_row.clear(); - sort_col.clear(); - } -}; - -/** - * class used by SparseForJacHessian to hold information relative to the - * Hessian so it does not need to be recomputed. - */ -class SparseForjacHessianWorkHes { -public: - /// version of user r array sorted by row or column - std::vector r_sort; - /// version of user c array sorted by row or column - std::vector c_sort; - /// mapping from sorted array indices to user array indices - std::vector k_sort; - /// number elements in the user sparse Hessian - size_t K; - - template - inline void prepare(const ADFun& fun, - const VectorSize& row, - const VectorSize& col) { - /** - * Code adapted from ADFun::SparseHessian() - */ - size_t n = fun.Domain(); - K = row.size(); - - if (r_sort.size() == 0) { - // create version of (row, col, k) sorted by row value - c_sort.resize(K); - r_sort.resize(K + 1); - k_sort.resize(K); - - // put sorting indices in k_sort - index_sort(row, k_sort); - - for (size_t k = 0; k < K; k++) { - r_sort[k] = row[ k_sort[k] ]; - c_sort[k] = col[ k_sort[k] ]; - } - r_sort[K] = n; - } -#ifndef NDEBUG - CPPAD_ASSERT_KNOWN(size_t(row.size()) == K && size_t(col.size()) == K, - "sparseForJacHessian: either r or c does not have the same size as ehs."); - CPPAD_ASSERT_KNOWN(r_sort.size() == K + 1 && - c_sort.size() == K && - k_sort.size() == K, - "sparseForJacHessian: invalid value in work."); - for (size_t k = 0; k < K; k++) { - CPPAD_ASSERT_KNOWN(row[k] < n, - "sparseForJacHessian: invalid value in r."); - CPPAD_ASSERT_KNOWN(col[k] < n, - "sparseForJacHessian: invalid value in c."); - CPPAD_ASSERT_KNOWN(k_sort[k] < K, - "sparseForJacHessian: invalid value in work."); - CPPAD_ASSERT_KNOWN(r_sort[k] == row[ k_sort[k] ], - "sparseForJacHessian: invalid value in work."); - CPPAD_ASSERT_KNOWN(c_sort[k] == col[ k_sort[k] ], - "sparseForJacHessian: invalid value in work."); - } -#endif - } - /// inform CppAD that this information needs to be recomputed - - inline void clear(void) { - r_sort.clear(); - c_sort.clear(); - k_sort.clear(); - } -}; - -/** - * class used by SparseForJacHessian to hold information so it does not need - * to be recomputed. - */ -class SparseForjacHessianWork { -public: - SparseForjacHessianWorkJac jac; - SparseForjacHessianWorkHes hes; - /// results of the coloring algorithm - std::vector color; - - template - inline void prepare(const ADFun& fun, - const VectorSize& jacRow, - const VectorSize& jacCol, - const VectorSize& hesRow, - const VectorSize& hesCol) { - size_t n = fun.Domain(); - - CPPAD_ASSERT_KNOWN(color.size() == 0 || color.size() == n, - "sparseForJacHessian: invalid value in work."); - if (color.size() != 0) { - for (size_t j = 0; j < n; j++) { - CPPAD_ASSERT_KNOWN(color[j] < n, - "sparseForJacHessian: invalid value in work."); - } - } - - jac.prepare(fun, jacRow, jacCol); - hes.prepare(fun, hesRow, hesCol); - } - /// inform CppAD that this information needs to be recomputed - - inline void clear(void) { - jac.clear(); - hes.clear(); - color.clear(); - } -}; - -template -inline void computeNotUsed(VectorSet& not_used, - VectorSet& sparsity, - VectorSet& r_used, - size_t m, - size_t n) { - - assert(not_used.n_set() == 0); - not_used.resize(m, n); - - for (size_t i = 0; i < n; i++) { - sparsity.begin(i); - size_t j = sparsity.next_element(); - while (j != sparsity.end()) { - if (!r_used.is_element(j, i)) - not_used.add_element(j, i); - j = sparsity.next_element(); - } - } -} - -template -inline size_t colorForwardJacobianHessian(const ADFun& fun, - const VectorSet& jac_p, - const VectorSet& hes_p, - SparseForjacHessianWork& work) { - /** - * Code adapted from ADFun::SparseJacobianForward() - */ - - size_t i, j1, j11, j2, c, k; - - size_t n = fun.Domain(); - size_t m = fun.Range(); - - std::vector& color = work.color; - - if (color.size() == 0) { - - color.resize(n); - - CPPAD_ASSERT_KNOWN(jac_p.size() == m, - "sparseForJacHessian: invalid jacobian sparsity pattern dimension."); - CPPAD_ASSERT_KNOWN(hes_p.size() == n, - "sparseForJacHessian: invalid hessian sparsity pattern dimension."); - - /** - * Jacobian - */ - // transpose sparsity pattern - typedef typename VectorSet::value_type Set_type; - typedef typename internal_sparsity::pattern_type Pattern_type; - Pattern_type p_transpose; - bool transpose = true; - sparsity_user2internal(p_transpose, jac_p, m, n, transpose); - //sparsity_user2internal(p_transpose, jac_p, n, m, transpose, "Invalid sparsity pattern"); - - - size_t jac_K = work.jac.K; - std::vector& jac_row = work.jac.user_row; - std::vector& jac_col = work.jac.user_col; - std::vector& sort_col = work.jac.sort_col; - - CPPAD_ASSERT_UNKNOWN(p_transpose.n_set() == n); - CPPAD_ASSERT_UNKNOWN(p_transpose.end() == m); - - // rows and columns that are in the returned jacobian - Pattern_type jac_r_used, jac_c_used; - jac_r_used.resize(n, m); - jac_c_used.resize(m, n); - - for (k = 0; k < jac_K; k++) { - CPPAD_ASSERT_UNKNOWN(jac_row[sort_col[k]] < m && jac_col[sort_col[k]] < n); - CPPAD_ASSERT_UNKNOWN(k == 0 || jac_col[sort_col[k - 1]] <= jac_col[sort_col[k]]); - CPPAD_ASSERT_KNOWN(p_transpose.is_element(jac_col[sort_col[k]], jac_row[sort_col[k]]), - "sparseForJacHessian: " - "a (row, col) pair is not in sparsity pattern."); - jac_r_used.add_element(jac_col[sort_col[k]], jac_row[sort_col[k]]); - jac_c_used.add_element(jac_row[sort_col[k]], jac_col[sort_col[k]]); - } - - // given a row index, which columns are non-zero and not used - Pattern_type jac_not_used; - computeNotUsed(jac_not_used, p_transpose, jac_c_used, m, n); - - /** - * Hessian - */ - Pattern_type hes_sparsity; - transpose = false; - sparsity_user2internal(hes_sparsity, hes_p, n, n, transpose); - //sparsity_user2internal(hes_sparsity, hes_p, n, n, transpose, "Invalid sparsity pattern"); - - size_t hes_K = work.hes.K; - std::vector& hes_row(work.hes.r_sort); - std::vector& hes_col(work.hes.c_sort); - - CPPAD_ASSERT_UNKNOWN(hes_sparsity.n_set() == n); - CPPAD_ASSERT_UNKNOWN(hes_sparsity.end() == n); - - // rows and columns that are in the returned hessian - Pattern_type hes_r_used, hes_c_used; - hes_r_used.resize(n, n); - hes_c_used.resize(n, n); - - for (k = 0; k < hes_K; k++) { - CPPAD_ASSERT_UNKNOWN(hes_row[k] < n && hes_col[k] < n); - CPPAD_ASSERT_UNKNOWN(k == 0 || hes_row[k - 1] <= hes_row[k]); - CPPAD_ASSERT_KNOWN(hes_sparsity.is_element(hes_row[k], hes_col[k]), - "sparseForJacHessian: a (row, col) pair is not in sparsity pattern."); - hes_r_used.add_element(hes_col[k], hes_row[k]); - hes_c_used.add_element(hes_row[k], hes_col[k]); - } - - // given a column index, which rows are non-zero and not used - Pattern_type hes_not_used; - computeNotUsed(hes_not_used, hes_sparsity, hes_r_used, n, n); - - // initial coloring - for (j1 = 0; j1 < n; j1++) { - color[j1] = j1; - } - - // See GreedyPartialD2Coloring Algorithm Section 3.6.2 of - // Graph Coloring in Optimization Revisited by - // Assefaw Gebremedhin, Fredrik Maane, Alex Pothen - vectorBool forbidden(n); - for (j1 = 1; j1 < n; j1++) { - // initialize all colors as ok for this column - // (value of forbidden for c > j does not matter) - for (c = 0; c <= j1; c++) - forbidden[c] = false; - - /** - * Jacobian - */ - // for each row that is non-zero for this column - p_transpose.begin(j1); - i = p_transpose.next_element(); - while (i != p_transpose.end()) { - // for each column that this row uses - jac_c_used.begin(i); - j11 = jac_c_used.next_element(); - while (j11 != jac_c_used.end()) { - // if this is not the same column, forbid its color - if (j11 < j1) - forbidden[ color[j11] ] = true; - j11 = jac_c_used.next_element(); - } - i = p_transpose.next_element(); - } - - // for each row that this column uses - jac_r_used.begin(j1); - i = jac_r_used.next_element(); - while (i != jac_r_used.end()) { - // For each column that is non-zero for this row - // (the used columns have already been checked above). - jac_not_used.begin(i); - j11 = jac_not_used.next_element(); - while (j11 != jac_not_used.end()) { - // if this is not the same column, forbid its color - if (j11 < j1) - forbidden[ color[j11] ] = true; - j11 = jac_not_used.next_element(); - } - i = jac_r_used.next_element(); - } - - /** - * Hessian - */ - // ----------------------------------------------------- - // Forbid colors that this row would destroy results for. - // for each column that is non-zero for this row - hes_sparsity.begin(j1); - j2 = hes_sparsity.next_element(); - while (j2 != hes_sparsity.end()) { - // for each row that this column uses - hes_r_used.begin(j2); - j11 = hes_r_used.next_element(); - while (j11 != hes_r_used.end()) { - // if this is not the same row, forbid its color - if (j11 < j1) - forbidden[ color[j11] ] = true; - j11 = hes_r_used.next_element(); - } - j2 = hes_sparsity.next_element(); - } - - // ------------------------------------------------------- - // Forbid colors that would destroy the results for this row. - // for each column that this row used - hes_c_used.begin(j1); - j2 = hes_c_used.next_element(); - while (j2 != hes_c_used.end()) { - // For each row that is non-zero for this column - // (the used rows have already been checked above). - hes_not_used.begin(j2); - j11 = hes_not_used.next_element(); - while (j11 != hes_not_used.end()) { - // if this is not the same row, forbid its color - if (j11 < j1) - forbidden[ color[j11] ] = true; - j11 = hes_not_used.next_element(); - } - j2 = hes_c_used.next_element(); - } - - - // pick the color with smallest index - c = 0; - while (forbidden[c]) { - c++; - CPPAD_ASSERT_UNKNOWN(c <= j1); - } - color[j1] = c; - } - } - - - size_t n_color = 1; - for (j1 = 0; j1 < n; j1++) - n_color = std::max(n_color, color[j1] + 1); - - return n_color; -} - -/** - * Compute user specified subset of a sparse Jacobian and a sparse Hessian. - * - * The C++ source code corresponding to this operation is - * @verbatim - * SparseForJacHessian(x, w, y, jac_p, jac_row, jac_col, jac, hes_p, hes_row, hes_col, hes, work) - * @endverbatim - * - * @tparam Base is the base type for the recording that is stored in - * this ADFun object. - * @tparam VectorBase is a simple vector class with elements of type @a Base. - * @tparam VectorSet is a simple vector class with elements of type @c bool - * or @c std::set. - * @tparam VectorSize is a simple vector class with elements of type @c size_t. - * - * @param x is a vector specifying the point at which to compute the Hessian. - * @param w is the weighting vector that defines a scalar valued function - * by a weighted sum of the components of the vector valued - * function $latex F(x)$$. - * @param y is a vector of the dependent variable values. - * @param jac_p is the sparsity pattern for the Jacobian that we are calculating. - * @param jac_row is the vector of row indices for the returned Jacobian values. - * @param jac_col is the vector of columns indices for the returned - * Jacobian values. It must have the same size are r. - * @param jac is the vector of Jacobian values. It must have the same size - * are r. The return value jac[k] is the partial - * of the row[k] component of the function with - * respect the the col[k] of its argument. - * @param hes_p is the sparsity pattern for the Hessian that we are calculating. - * @param hes_row is the vector of row indices for the returned Hessian values. - * @param hes_col is the vector of columns indices for the returned Hessian values. - * It must have the same size are r. - * @param hes is the vector of Hessian values. It must have the same size - * as r. The return value hes[k] is the second - * partial of \f$ w^{\rm T} F(x)\f$ with respect to the - * row[k] and col[k] component of - * \f$ x\f$. - * @param work contains information that depends on the function object, - * sparsity pattern, @c jac_row, @c jac_col, @c hes_row, and - * @c hes_col vector. If these values are the same, @c work does - * not need to be recomputed. - * @return Is the number of first order forward and second order reverse - * sweeps used to compute the requested values. The total work, not - * counting the zero order forward sweep, or the time to combine - * computations, is proportional to this return value. - */ -template -size_t sparseForJacHessian(ADFun& fun, - const VectorBase& x, - const VectorBase& w, - VectorBase& y, - const VectorSet& jac_p, - const VectorSize& jac_row, - const VectorSize& jac_col, - VectorBase& jac, - const VectorSet& hes_p, - const VectorSize& hes_row, - const VectorSize& hes_col, - VectorBase& hes, - SparseForjacHessianWork& work) { - std::vector vw(1); - std::vector vhes(1); - vw[0] = w; - vhes[0] = hes; - - size_t n_sweep = sparseForJacHessian(fun, - x, vw, - y, - jac_p, jac_row, jac_col, jac, - hes_p, hes_row, hes_col, vhes, - work); - - hes = vhes[0]; - - return n_sweep; -} - -template -size_t sparseForJacHessian(ADFun& fun, - const VectorBase& x, - const VectorVectorBase& w, - VectorBase& y, - const VectorSet& jac_p, - const VectorSize& jac_row, - const VectorSize& jac_col, - VectorBase& jac, - const VectorSet& hes_p, - const VectorSize& hes_row, - const VectorSize& hes_col, - VectorVectorBase& hes, - SparseForjacHessianWork& work) { - using CppAD::vectorBool; - size_t j1, k, c; - - size_t n = fun.Domain(); - size_t m = fun.Range(); - - size_t nH = size_t(hes.size()); - size_t jac_K = size_t(jac_row.size()); - size_t hes_K = size_t(hes_row.size()); - - CPPADCG_ASSERT_KNOWN(size_t(x.size()) == n, - "sparseForJacHessian: size of x not equal domain dimension for f."); - - CPPADCG_ASSERT_KNOWN(size_t(w.size()) == nH, - "sparseForJacHessian: size of w not equal to the size of hes."); - - const std::vector& jac_scol = work.jac.sort_col; - const std::vector& hes_srow = work.hes.r_sort; - const std::vector& hes_scol = work.hes.c_sort; - const std::vector& hes_user_k = work.hes.k_sort; - const std::vector& color = work.color; - - // some values - const Base zero(0); - const Base one(1); - - // check VectorBase is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_UNKNOWN(size_t(x.size()) == n); - - work.prepare(fun, jac_row, jac_col, hes_row, hes_col); - - /** - * coloring - */ - size_t n_color = colorForwardJacobianHessian(fun, jac_p, hes_p, work); - - - // Point at which we are evaluating the Hessian - y = fun.Forward(0, x); - - // direction vector for calls to forward (columns of jacobian and rows of the Hessian) - VectorBase u(n); - - // location for return values from forward - VectorBase dy(m); - - // location for return values from reverse (columns of the Hessian) - VectorBase ddw(2 * n); - - // initialize the return value - for (k = 0; k < jac_K; k++) - jac[k] = zero; - for (size_t h = 0; h < nH; h++) { - VectorBase& hesh = hes[h]; - for (k = 0; k < hes_K; k++) - hesh[k] = zero; - } - - // loop over colors - size_t n_sweep = 0; - for (c = 0; c < n_color; c++) { - - bool anyJac = false; - size_t kJac = 0; - for (j1 = 0; j1 < n; j1++) { - if (color[j1] == c) { - // find first k such that col[sort_col[k]] has color c - while (work.jac.user_col[jac_scol[kJac]] < j1) - kJac++; - anyJac = work.jac.user_col[jac_scol[kJac]] == j1; - if (anyJac) - break; - } - } - - bool anyHes = false; - size_t kHessStart = 0; - for (j1 = 0; j1 < n; j1++) { - if (color[j1] == c) { - // find first k such that row[k] has color c - while (hes_srow[kHessStart] < j1) - kHessStart++; - anyHes = hes_srow[kHessStart] == j1; - if (anyHes) - break; - } - } - - if (anyJac || anyHes) { - n_sweep++; - // combine all rows with this color - for (j1 = 0; j1 < n; j1++) { - u[j1] = zero; - if (color[j1] == c) - u[j1] = one; - } - // call forward mode for all these rows at once - dy = fun.Forward(1, u); - - if (anyJac) { - // set the corresponding components of the result - for (j1 = 0; j1 < n; j1++) { - if (color[j1] == c) { - // find first index in c for this jacobian column - while (work.jac.user_col[jac_scol[kJac]] < j1) - kJac++; - // extract the row results for this column - while (work.jac.user_col[jac_scol[kJac]] == j1) { - jac[ jac_scol[kJac] ] = dy[ work.jac.user_row[jac_scol[kJac]] ]; - kJac++; - } - } - } - } - - if (anyHes) { - n_sweep++; - - for (size_t h = 0; h < nH; h++) { - // evaluate derivative of w^T * F'(x) * u - ddw = fun.Reverse(2, w[h]); - - VectorBase& hesh = hes[h]; - - // set the corresponding components of the result - size_t kHess = kHessStart; - for (j1 = 0; j1 < n; j1++) { - if (color[j1] == c) { - // find first index in c for this column - while (hes_srow[kHess] < j1) - kHess++; - // extract the results for this row - while (hes_srow[kHess] == j1) { - size_t j2 = hes_scol[kHess]; - hesh[ hes_user_k[kHess] ] = ddw[ j2 * 2 + 1 ]; - kHess++; - } - } - } - } - } - } - } - return n_sweep; -} - -} -} - -#endif diff --git a/ct_core/include/ct/external/cppad/cg/extra/sparsity.hpp b/ct_core/include/ct/external/cppad/cg/extra/sparsity.hpp deleted file mode 100644 index 380a6a57c..000000000 --- a/ct_core/include/ct/external/cppad/cg/extra/sparsity.hpp +++ /dev/null @@ -1,315 +0,0 @@ -#ifndef CPPAD_EXTRA_SPARSITY_INCLUDED -#define CPPAD_EXTRA_SPARSITY_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -inline VectorBool jacobianForwardSparsity(ADFun& fun) { - size_t n = fun.Domain(); - - VectorBool r(n * n); - for (size_t j = 0; j < n; j++) { - for (size_t k = 0; k < n; k++) - r[j * n + k] = false; - r[j * n + j] = true; - } - return fun.ForSparseJac(n, r); - -} - -template -inline VectorBool jacobianReverseSparsity(ADFun& fun) { - size_t m = fun.Range(); - - VectorBool s(m * m); - for (size_t i = 0; i < m; i++) { - for (size_t k = 0; k < m; k++) - s[i * m + k] = false; - s[i * m + i] = true; - } - return fun.RevSparseJac(m, s); -} - -template -inline VectorSet jacobianForwardSparsitySet(ADFun& fun) { - size_t n = fun.Domain(); - - VectorSet r(n); - for (size_t i = 0; i < n; i++) - r[i].insert(i); - - return fun.ForSparseJac(n, r); -} - -template -inline VectorSet jacobianReverseSparsitySet(ADFun& fun) { - size_t m = fun.Range(); - - VectorSet s_s(m); - for (size_t i = 0; i < m; i++) - s_s[i].insert(i); - - return fun.RevSparseJac(m, s_s); -} - -/** - * Determines the Jacobian sparsity for a model - * - * @param fun The model - * @return The Jacobian sparsity - */ -template -inline VectorBool jacobianSparsity(ADFun& fun) { - size_t m = fun.Range(); - size_t n = fun.Domain(); - - if (n <= m) { - // use forward mode - return jacobianForwardSparsity (fun); - } else { - // use reverse mode - return jacobianReverseSparsity (fun); - } -} - -/** - * Determines the Jacobian sparsity for a model - * - * @param fun The model - * @return The Jacobian sparsity - */ -template -inline VectorSet jacobianSparsitySet(ADFun& fun) { - size_t m = fun.Range(); - size_t n = fun.Domain(); - - if (n <= m) { - // use forward mode - return jacobianForwardSparsitySet (fun); - } else { - // use reverse mode - return jacobianReverseSparsitySet (fun); - } -} - -/** - * Estimates the work load of forward vs reverse mode for the evaluation of - * a Jacobian - * - * @return true if the foward mode should be used, false for the reverse mode - */ -inline bool estimateBestJacobianADMode(const std::vector& jacRows, - const std::vector& jacCols) { - std::set rows, cols; - rows.insert(jacRows.begin(), jacRows.end()); - size_t workReverse = rows.size(); - cols.insert(jacCols.begin(), jacCols.end()); - size_t workForward = cols.size(); - - return workForward <= workReverse; -} - -/** - * Determines the sum of the hessian sparsities for all the dependent - * variables in a model - * - * @param fun The model - * @return The sum of the hessian sparsities - */ -template -inline VectorBool hessianSparsity(ADFun& fun, - bool transpose = false) { - size_t m = fun.Range(); - size_t n = fun.Domain(); - - /** - * Determine the sparsity pattern p for Hessian of w^T F - */ - VectorBool r(n * n); // identity matrix - for (size_t j = 0; j < n; j++) { - for (size_t k = 0; k < n; k++) - r[j * n + k] = false; - r[j * n + j] = true; - } - fun.ForSparseJac(n, r); - - VectorBool s(m); - for (size_t i = 0; i < m; i++) - s[i] = true; - return fun.RevSparseHes(n, s, transpose); -} - -template -inline VectorSet hessianSparsitySet(ADFun& fun, - const std::set& w, - bool transpose = false) { - size_t n = fun.Domain(); - - /** - * Determine the sparsity pattern p for Hessian of w^T F - */ - VectorSet r(n); // identity matrix - for (size_t j = 0; j < n; j++) - r[j].insert(j); - fun.ForSparseJac(n, r); - - VectorSet s(1); - s[0] = w; - - return fun.RevSparseHes(n, s, transpose); -} - -template -inline VectorSet hessianSparsitySet(ADFun& fun, bool transpose = false) { - size_t m = fun.Range(); - - std::set w; - for (size_t i = 0; i < m; i++) { - w.insert(i); - } - return hessianSparsitySet(fun, w, transpose); -} - -/** - * Determines the hessian sparsity for a given dependent variable/equation - * in a model - * - * @param fun The model - * @param i The dependent variable/equation index - * @return The hessian sparsity - */ -template -inline VectorBool hessianSparsity(ADFun& fun, - size_t i, - bool transpose = false) { - size_t m = fun.Range(); - size_t n = fun.Domain(); - - /** - * Determine the sparsity pattern p for Hessian of w^T F - */ - VectorBool r(n * n); // identity matrix - for (size_t j = 0; j < n; j++) { - for (size_t k = 0; k < n; k++) - r[j * n + k] = false; - r[j * n + j] = true; - } - fun.ForSparseJac(n, r); - - VectorBool s(m); - for (size_t ii = 0; ii < m; ii++) - s[ii] = false; - s[i] = true; - return fun.RevSparseHes(n, s, transpose); -} - -template -inline VectorSet hessianSparsitySet(ADFun& fun, - size_t i, - bool transpose = false) { - size_t n = fun.Domain(); - - VectorSet r(n); // identity matrix - for (size_t j = 0; j < n; j++) - r[j].insert(j); - fun.ForSparseJac(n, r); - - VectorSet s(1); - s[0].insert(i); - - return fun.RevSparseHes(n, s, transpose); -} - -template -inline void generateSparsityIndexes(const VectorBool& sparsity, - size_t m, - size_t n, - VectorSize& row, - VectorSize& col) { - assert(sparsity.size() == m * n); - - // determine total number of non zeros - size_t nnz = 0; - for (size_t i = 0; i < sparsity.size(); i++) { - if (sparsity[i]) - nnz++; - } - - row.resize(nnz); - col.resize(nnz); - - // save the indexes - nnz = 0; - for (size_t i = 0; i < m; i++) { - for (size_t j = 0; j < n; j++) { - if (sparsity[i * n + j]) { - row[nnz] = i; - col[nnz] = j; - nnz++; - } - } - } - - assert(nnz == row.size()); -} - -template -inline void generateSparsityIndexes(const VectorSet& sparsity, - VectorSize& row, - VectorSize& col) { - size_t m = sparsity.size(); - - // determine total number of non zeros - size_t nnz = 0; - for (size_t i = 0; i < m; i++) { - nnz += sparsity[i].size(); - } - - row.resize(nnz); - col.resize(nnz); - if (nnz == 0) - return; - - // save the indexes - nnz = 0; - for (size_t i = 0; i < m; i++) { - const std::set& rowSparsity = sparsity[i]; - size_t rowNnz = rowSparsity.size(); - std::fill(&row[0] + nnz, &row[0] + nnz + rowNnz, i); - std::copy(rowSparsity.begin(), rowSparsity.end(), &col[0] + nnz); - nnz += rowNnz; - } -} - -template -inline void generateSparsitySet(const VectorSize& row, - const VectorSize& col, - VectorSet& sparsity) { - assert(row.size() == col.size()); - - size_t nnz = row.size(); - for (size_t e = 0; e < nnz; e++) { - sparsity[row[e]].insert(col[e]); - } -} - -} // END cg namespace -} // END CppAD namespace - -#endif - diff --git a/ct_core/include/ct/external/cppad/cg/gpl3.txt b/ct_core/include/ct/external/cppad/cg/gpl3.txt deleted file mode 100644 index 20d40b6bc..000000000 --- a/ct_core/include/ct/external/cppad/cg/gpl3.txt +++ /dev/null @@ -1,674 +0,0 @@ - GNU GENERAL PUBLIC LICENSE - Version 3, 29 June 2007 - - Copyright (C) 2007 Free Software Foundation, Inc. - Everyone is permitted to copy and distribute verbatim copies - of this license document, but changing it is not allowed. - - Preamble - - The GNU General Public License is a free, copyleft license for -software and other kinds of works. - - The licenses for most software and other practical works are designed -to take away your freedom to share and change the works. By contrast, -the GNU General Public License is intended to guarantee your freedom to -share and change all versions of a program--to make sure it remains free -software for all its users. We, the Free Software Foundation, use the -GNU General Public License for most of our software; it applies also to -any other work released this way by its authors. You can apply it to -your programs, too. - - When we speak of free software, we are referring to freedom, not -price. Our General Public Licenses are designed to make sure that you -have the freedom to distribute copies of free software (and charge for -them if you wish), that you receive source code or can get it if you -want it, that you can change the software or use pieces of it in new -free programs, and that you know you can do these things. - - To protect your rights, we need to prevent others from denying you -these rights or asking you to surrender the rights. Therefore, you have -certain responsibilities if you distribute copies of the software, or if -you modify it: responsibilities to respect the freedom of others. - - For example, if you distribute copies of such a program, whether -gratis or for a fee, you must pass on to the recipients the same -freedoms that you received. You must make sure that they, too, receive -or can get the source code. And you must show them these terms so they -know their rights. - - Developers that use the GNU GPL protect your rights with two steps: -(1) assert copyright on the software, and (2) offer you this License -giving you legal permission to copy, distribute and/or modify it. - - For the developers' and authors' protection, the GPL clearly explains -that there is no warranty for this free software. For both users' and -authors' sake, the GPL requires that modified versions be marked as -changed, so that their problems will not be attributed erroneously to -authors of previous versions. - - Some devices are designed to deny users access to install or run -modified versions of the software inside them, although the manufacturer -can do so. This is fundamentally incompatible with the aim of -protecting users' freedom to change the software. The systematic -pattern of such abuse occurs in the area of products for individuals to -use, which is precisely where it is most unacceptable. Therefore, we -have designed this version of the GPL to prohibit the practice for those -products. If such problems arise substantially in other domains, we -stand ready to extend this provision to those domains in future versions -of the GPL, as needed to protect the freedom of users. - - Finally, every program is threatened constantly by software patents. -States should not allow patents to restrict development and use of -software on general-purpose computers, but in those that do, we wish to -avoid the special danger that patents applied to a free program could -make it effectively proprietary. To prevent this, the GPL assures that -patents cannot be used to render the program non-free. - - The precise terms and conditions for copying, distribution and -modification follow. - - TERMS AND CONDITIONS - - 0. Definitions. - - "This License" refers to version 3 of the GNU General Public License. - - "Copyright" also means copyright-like laws that apply to other kinds of -works, such as semiconductor masks. - - "The Program" refers to any copyrightable work licensed under this -License. Each licensee is addressed as "you". "Licensees" and -"recipients" may be individuals or organizations. - - To "modify" a work means to copy from or adapt all or part of the work -in a fashion requiring copyright permission, other than the making of an -exact copy. The resulting work is called a "modified version" of the -earlier work or a work "based on" the earlier work. - - A "covered work" means either the unmodified Program or a work based -on the Program. - - To "propagate" a work means to do anything with it that, without -permission, would make you directly or secondarily liable for -infringement under applicable copyright law, except executing it on a -computer or modifying a private copy. Propagation includes copying, -distribution (with or without modification), making available to the -public, and in some countries other activities as well. - - To "convey" a work means any kind of propagation that enables other -parties to make or receive copies. Mere interaction with a user through -a computer network, with no transfer of a copy, is not conveying. - - An interactive user interface displays "Appropriate Legal Notices" -to the extent that it includes a convenient and prominently visible -feature that (1) displays an appropriate copyright notice, and (2) -tells the user that there is no warranty for the work (except to the -extent that warranties are provided), that licensees may convey the -work under this License, and how to view a copy of this License. If -the interface presents a list of user commands or options, such as a -menu, a prominent item in the list meets this criterion. - - 1. Source Code. - - The "source code" for a work means the preferred form of the work -for making modifications to it. "Object code" means any non-source -form of a work. - - A "Standard Interface" means an interface that either is an official -standard defined by a recognized standards body, or, in the case of -interfaces specified for a particular programming language, one that -is widely used among developers working in that language. - - The "System Libraries" of an executable work include anything, other -than the work as a whole, that (a) is included in the normal form of -packaging a Major Component, but which is not part of that Major -Component, and (b) serves only to enable use of the work with that -Major Component, or to implement a Standard Interface for which an -implementation is available to the public in source code form. A -"Major Component", in this context, means a major essential component -(kernel, window system, and so on) of the specific operating system -(if any) on which the executable work runs, or a compiler used to -produce the work, or an object code interpreter used to run it. - - The "Corresponding Source" for a work in object code form means all -the source code needed to generate, install, and (for an executable -work) run the object code and to modify the work, including scripts to -control those activities. However, it does not include the work's -System Libraries, or general-purpose tools or generally available free -programs which are used unmodified in performing those activities but -which are not part of the work. For example, Corresponding Source -includes interface definition files associated with source files for -the work, and the source code for shared libraries and dynamically -linked subprograms that the work is specifically designed to require, -such as by intimate data communication or control flow between those -subprograms and other parts of the work. - - The Corresponding Source need not include anything that users -can regenerate automatically from other parts of the Corresponding -Source. - - The Corresponding Source for a work in source code form is that -same work. - - 2. Basic Permissions. - - All rights granted under this License are granted for the term of -copyright on the Program, and are irrevocable provided the stated -conditions are met. This License explicitly affirms your unlimited -permission to run the unmodified Program. The output from running a -covered work is covered by this License only if the output, given its -content, constitutes a covered work. This License acknowledges your -rights of fair use or other equivalent, as provided by copyright law. - - You may make, run and propagate covered works that you do not -convey, without conditions so long as your license otherwise remains -in force. You may convey covered works to others for the sole purpose -of having them make modifications exclusively for you, or provide you -with facilities for running those works, provided that you comply with -the terms of this License in conveying all material for which you do -not control copyright. Those thus making or running the covered works -for you must do so exclusively on your behalf, under your direction -and control, on terms that prohibit them from making any copies of -your copyrighted material outside their relationship with you. - - Conveying under any other circumstances is permitted solely under -the conditions stated below. Sublicensing is not allowed; section 10 -makes it unnecessary. - - 3. Protecting Users' Legal Rights From Anti-Circumvention Law. - - No covered work shall be deemed part of an effective technological -measure under any applicable law fulfilling obligations under article -11 of the WIPO copyright treaty adopted on 20 December 1996, or -similar laws prohibiting or restricting circumvention of such -measures. - - When you convey a covered work, you waive any legal power to forbid -circumvention of technological measures to the extent such circumvention -is effected by exercising rights under this License with respect to -the covered work, and you disclaim any intention to limit operation or -modification of the work as a means of enforcing, against the work's -users, your or third parties' legal rights to forbid circumvention of -technological measures. - - 4. Conveying Verbatim Copies. - - You may convey verbatim copies of the Program's source code as you -receive it, in any medium, provided that you conspicuously and -appropriately publish on each copy an appropriate copyright notice; -keep intact all notices stating that this License and any -non-permissive terms added in accord with section 7 apply to the code; -keep intact all notices of the absence of any warranty; and give all -recipients a copy of this License along with the Program. - - You may charge any price or no price for each copy that you convey, -and you may offer support or warranty protection for a fee. - - 5. Conveying Modified Source Versions. - - You may convey a work based on the Program, or the modifications to -produce it from the Program, in the form of source code under the -terms of section 4, provided that you also meet all of these conditions: - - a) The work must carry prominent notices stating that you modified - it, and giving a relevant date. - - b) The work must carry prominent notices stating that it is - released under this License and any conditions added under section - 7. This requirement modifies the requirement in section 4 to - "keep intact all notices". - - c) You must license the entire work, as a whole, under this - License to anyone who comes into possession of a copy. This - License will therefore apply, along with any applicable section 7 - additional terms, to the whole of the work, and all its parts, - regardless of how they are packaged. This License gives no - permission to license the work in any other way, but it does not - invalidate such permission if you have separately received it. - - d) If the work has interactive user interfaces, each must display - Appropriate Legal Notices; however, if the Program has interactive - interfaces that do not display Appropriate Legal Notices, your - work need not make them do so. - - A compilation of a covered work with other separate and independent -works, which are not by their nature extensions of the covered work, -and which are not combined with it such as to form a larger program, -in or on a volume of a storage or distribution medium, is called an -"aggregate" if the compilation and its resulting copyright are not -used to limit the access or legal rights of the compilation's users -beyond what the individual works permit. Inclusion of a covered work -in an aggregate does not cause this License to apply to the other -parts of the aggregate. - - 6. Conveying Non-Source Forms. - - You may convey a covered work in object code form under the terms -of sections 4 and 5, provided that you also convey the -machine-readable Corresponding Source under the terms of this License, -in one of these ways: - - a) Convey the object code in, or embodied in, a physical product - (including a physical distribution medium), accompanied by the - Corresponding Source fixed on a durable physical medium - customarily used for software interchange. - - b) Convey the object code in, or embodied in, a physical product - (including a physical distribution medium), accompanied by a - written offer, valid for at least three years and valid for as - long as you offer spare parts or customer support for that product - model, to give anyone who possesses the object code either (1) a - copy of the Corresponding Source for all the software in the - product that is covered by this License, on a durable physical - medium customarily used for software interchange, for a price no - more than your reasonable cost of physically performing this - conveying of source, or (2) access to copy the - Corresponding Source from a network server at no charge. - - c) Convey individual copies of the object code with a copy of the - written offer to provide the Corresponding Source. This - alternative is allowed only occasionally and noncommercially, and - only if you received the object code with such an offer, in accord - with subsection 6b. - - d) Convey the object code by offering access from a designated - place (gratis or for a charge), and offer equivalent access to the - Corresponding Source in the same way through the same place at no - further charge. You need not require recipients to copy the - Corresponding Source along with the object code. If the place to - copy the object code is a network server, the Corresponding Source - may be on a different server (operated by you or a third party) - that supports equivalent copying facilities, provided you maintain - clear directions next to the object code saying where to find the - Corresponding Source. Regardless of what server hosts the - Corresponding Source, you remain obligated to ensure that it is - available for as long as needed to satisfy these requirements. - - e) Convey the object code using peer-to-peer transmission, provided - you inform other peers where the object code and Corresponding - Source of the work are being offered to the general public at no - charge under subsection 6d. - - A separable portion of the object code, whose source code is excluded -from the Corresponding Source as a System Library, need not be -included in conveying the object code work. - - A "User Product" is either (1) a "consumer product", which means any -tangible personal property which is normally used for personal, family, -or household purposes, or (2) anything designed or sold for incorporation -into a dwelling. In determining whether a product is a consumer product, -doubtful cases shall be resolved in favor of coverage. For a particular -product received by a particular user, "normally used" refers to a -typical or common use of that class of product, regardless of the status -of the particular user or of the way in which the particular user -actually uses, or expects or is expected to use, the product. A product -is a consumer product regardless of whether the product has substantial -commercial, industrial or non-consumer uses, unless such uses represent -the only significant mode of use of the product. - - "Installation Information" for a User Product means any methods, -procedures, authorization keys, or other information required to install -and execute modified versions of a covered work in that User Product from -a modified version of its Corresponding Source. The information must -suffice to ensure that the continued functioning of the modified object -code is in no case prevented or interfered with solely because -modification has been made. - - If you convey an object code work under this section in, or with, or -specifically for use in, a User Product, and the conveying occurs as -part of a transaction in which the right of possession and use of the -User Product is transferred to the recipient in perpetuity or for a -fixed term (regardless of how the transaction is characterized), the -Corresponding Source conveyed under this section must be accompanied -by the Installation Information. But this requirement does not apply -if neither you nor any third party retains the ability to install -modified object code on the User Product (for example, the work has -been installed in ROM). - - The requirement to provide Installation Information does not include a -requirement to continue to provide support service, warranty, or updates -for a work that has been modified or installed by the recipient, or for -the User Product in which it has been modified or installed. Access to a -network may be denied when the modification itself materially and -adversely affects the operation of the network or violates the rules and -protocols for communication across the network. - - Corresponding Source conveyed, and Installation Information provided, -in accord with this section must be in a format that is publicly -documented (and with an implementation available to the public in -source code form), and must require no special password or key for -unpacking, reading or copying. - - 7. Additional Terms. - - "Additional permissions" are terms that supplement the terms of this -License by making exceptions from one or more of its conditions. -Additional permissions that are applicable to the entire Program shall -be treated as though they were included in this License, to the extent -that they are valid under applicable law. If additional permissions -apply only to part of the Program, that part may be used separately -under those permissions, but the entire Program remains governed by -this License without regard to the additional permissions. - - When you convey a copy of a covered work, you may at your option -remove any additional permissions from that copy, or from any part of -it. (Additional permissions may be written to require their own -removal in certain cases when you modify the work.) You may place -additional permissions on material, added by you to a covered work, -for which you have or can give appropriate copyright permission. - - Notwithstanding any other provision of this License, for material you -add to a covered work, you may (if authorized by the copyright holders of -that material) supplement the terms of this License with terms: - - a) Disclaiming warranty or limiting liability differently from the - terms of sections 15 and 16 of this License; or - - b) Requiring preservation of specified reasonable legal notices or - author attributions in that material or in the Appropriate Legal - Notices displayed by works containing it; or - - c) Prohibiting misrepresentation of the origin of that material, or - requiring that modified versions of such material be marked in - reasonable ways as different from the original version; or - - d) Limiting the use for publicity purposes of names of licensors or - authors of the material; or - - e) Declining to grant rights under trademark law for use of some - trade names, trademarks, or service marks; or - - f) Requiring indemnification of licensors and authors of that - material by anyone who conveys the material (or modified versions of - it) with contractual assumptions of liability to the recipient, for - any liability that these contractual assumptions directly impose on - those licensors and authors. - - All other non-permissive additional terms are considered "further -restrictions" within the meaning of section 10. If the Program as you -received it, or any part of it, contains a notice stating that it is -governed by this License along with a term that is a further -restriction, you may remove that term. If a license document contains -a further restriction but permits relicensing or conveying under this -License, you may add to a covered work material governed by the terms -of that license document, provided that the further restriction does -not survive such relicensing or conveying. - - If you add terms to a covered work in accord with this section, you -must place, in the relevant source files, a statement of the -additional terms that apply to those files, or a notice indicating -where to find the applicable terms. - - Additional terms, permissive or non-permissive, may be stated in the -form of a separately written license, or stated as exceptions; -the above requirements apply either way. - - 8. Termination. - - You may not propagate or modify a covered work except as expressly -provided under this License. Any attempt otherwise to propagate or -modify it is void, and will automatically terminate your rights under -this License (including any patent licenses granted under the third -paragraph of section 11). - - However, if you cease all violation of this License, then your -license from a particular copyright holder is reinstated (a) -provisionally, unless and until the copyright holder explicitly and -finally terminates your license, and (b) permanently, if the copyright -holder fails to notify you of the violation by some reasonable means -prior to 60 days after the cessation. - - Moreover, your license from a particular copyright holder is -reinstated permanently if the copyright holder notifies you of the -violation by some reasonable means, this is the first time you have -received notice of violation of this License (for any work) from that -copyright holder, and you cure the violation prior to 30 days after -your receipt of the notice. - - Termination of your rights under this section does not terminate the -licenses of parties who have received copies or rights from you under -this License. If your rights have been terminated and not permanently -reinstated, you do not qualify to receive new licenses for the same -material under section 10. - - 9. Acceptance Not Required for Having Copies. - - You are not required to accept this License in order to receive or -run a copy of the Program. Ancillary propagation of a covered work -occurring solely as a consequence of using peer-to-peer transmission -to receive a copy likewise does not require acceptance. However, -nothing other than this License grants you permission to propagate or -modify any covered work. These actions infringe copyright if you do -not accept this License. Therefore, by modifying or propagating a -covered work, you indicate your acceptance of this License to do so. - - 10. Automatic Licensing of Downstream Recipients. - - Each time you convey a covered work, the recipient automatically -receives a license from the original licensors, to run, modify and -propagate that work, subject to this License. You are not responsible -for enforcing compliance by third parties with this License. - - An "entity transaction" is a transaction transferring control of an -organization, or substantially all assets of one, or subdividing an -organization, or merging organizations. If propagation of a covered -work results from an entity transaction, each party to that -transaction who receives a copy of the work also receives whatever -licenses to the work the party's predecessor in interest had or could -give under the previous paragraph, plus a right to possession of the -Corresponding Source of the work from the predecessor in interest, if -the predecessor has it or can get it with reasonable efforts. - - You may not impose any further restrictions on the exercise of the -rights granted or affirmed under this License. For example, you may -not impose a license fee, royalty, or other charge for exercise of -rights granted under this License, and you may not initiate litigation -(including a cross-claim or counterclaim in a lawsuit) alleging that -any patent claim is infringed by making, using, selling, offering for -sale, or importing the Program or any portion of it. - - 11. Patents. - - A "contributor" is a copyright holder who authorizes use under this -License of the Program or a work on which the Program is based. The -work thus licensed is called the contributor's "contributor version". - - A contributor's "essential patent claims" are all patent claims -owned or controlled by the contributor, whether already acquired or -hereafter acquired, that would be infringed by some manner, permitted -by this License, of making, using, or selling its contributor version, -but do not include claims that would be infringed only as a -consequence of further modification of the contributor version. For -purposes of this definition, "control" includes the right to grant -patent sublicenses in a manner consistent with the requirements of -this License. - - Each contributor grants you a non-exclusive, worldwide, royalty-free -patent license under the contributor's essential patent claims, to -make, use, sell, offer for sale, import and otherwise run, modify and -propagate the contents of its contributor version. - - In the following three paragraphs, a "patent license" is any express -agreement or commitment, however denominated, not to enforce a patent -(such as an express permission to practice a patent or covenant not to -sue for patent infringement). To "grant" such a patent license to a -party means to make such an agreement or commitment not to enforce a -patent against the party. - - If you convey a covered work, knowingly relying on a patent license, -and the Corresponding Source of the work is not available for anyone -to copy, free of charge and under the terms of this License, through a -publicly available network server or other readily accessible means, -then you must either (1) cause the Corresponding Source to be so -available, or (2) arrange to deprive yourself of the benefit of the -patent license for this particular work, or (3) arrange, in a manner -consistent with the requirements of this License, to extend the patent -license to downstream recipients. "Knowingly relying" means you have -actual knowledge that, but for the patent license, your conveying the -covered work in a country, or your recipient's use of the covered work -in a country, would infringe one or more identifiable patents in that -country that you have reason to believe are valid. - - If, pursuant to or in connection with a single transaction or -arrangement, you convey, or propagate by procuring conveyance of, a -covered work, and grant a patent license to some of the parties -receiving the covered work authorizing them to use, propagate, modify -or convey a specific copy of the covered work, then the patent license -you grant is automatically extended to all recipients of the covered -work and works based on it. - - A patent license is "discriminatory" if it does not include within -the scope of its coverage, prohibits the exercise of, or is -conditioned on the non-exercise of one or more of the rights that are -specifically granted under this License. You may not convey a covered -work if you are a party to an arrangement with a third party that is -in the business of distributing software, under which you make payment -to the third party based on the extent of your activity of conveying -the work, and under which the third party grants, to any of the -parties who would receive the covered work from you, a discriminatory -patent license (a) in connection with copies of the covered work -conveyed by you (or copies made from those copies), or (b) primarily -for and in connection with specific products or compilations that -contain the covered work, unless you entered into that arrangement, -or that patent license was granted, prior to 28 March 2007. - - Nothing in this License shall be construed as excluding or limiting -any implied license or other defenses to infringement that may -otherwise be available to you under applicable patent law. - - 12. No Surrender of Others' Freedom. - - If conditions are imposed on you (whether by court order, agreement or -otherwise) that contradict the conditions of this License, they do not -excuse you from the conditions of this License. If you cannot convey a -covered work so as to satisfy simultaneously your obligations under this -License and any other pertinent obligations, then as a consequence you may -not convey it at all. For example, if you agree to terms that obligate you -to collect a royalty for further conveying from those to whom you convey -the Program, the only way you could satisfy both those terms and this -License would be to refrain entirely from conveying the Program. - - 13. Use with the GNU Affero General Public License. - - Notwithstanding any other provision of this License, you have -permission to link or combine any covered work with a work licensed -under version 3 of the GNU Affero General Public License into a single -combined work, and to convey the resulting work. The terms of this -License will continue to apply to the part which is the covered work, -but the special requirements of the GNU Affero General Public License, -section 13, concerning interaction through a network will apply to the -combination as such. - - 14. Revised Versions of this License. - - The Free Software Foundation may publish revised and/or new versions of -the GNU General Public License from time to time. Such new versions will -be similar in spirit to the present version, but may differ in detail to -address new problems or concerns. - - Each version is given a distinguishing version number. If the -Program specifies that a certain numbered version of the GNU General -Public License "or any later version" applies to it, you have the -option of following the terms and conditions either of that numbered -version or of any later version published by the Free Software -Foundation. If the Program does not specify a version number of the -GNU General Public License, you may choose any version ever published -by the Free Software Foundation. - - If the Program specifies that a proxy can decide which future -versions of the GNU General Public License can be used, that proxy's -public statement of acceptance of a version permanently authorizes you -to choose that version for the Program. - - Later license versions may give you additional or different -permissions. However, no additional obligations are imposed on any -author or copyright holder as a result of your choosing to follow a -later version. - - 15. Disclaimer of Warranty. - - THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY -APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT -HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY -OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, -THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR -PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM -IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF -ALL NECESSARY SERVICING, REPAIR OR CORRECTION. - - 16. Limitation of Liability. - - IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING -WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS -THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY -GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE -USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF -DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD -PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), -EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF -SUCH DAMAGES. - - 17. Interpretation of Sections 15 and 16. - - If the disclaimer of warranty and limitation of liability provided -above cannot be given local legal effect according to their terms, -reviewing courts shall apply local law that most closely approximates -an absolute waiver of all civil liability in connection with the -Program, unless a warranty or assumption of liability accompanies a -copy of the Program in return for a fee. - - END OF TERMS AND CONDITIONS - - How to Apply These Terms to Your New Programs - - If you develop a new program, and you want it to be of the greatest -possible use to the public, the best way to achieve this is to make it -free software which everyone can redistribute and change under these terms. - - To do so, attach the following notices to the program. It is safest -to attach them to the start of each source file to most effectively -state the exclusion of warranty; and each file should have at least -the "copyright" line and a pointer to where the full notice is found. - - - Copyright (C) - - This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - -Also add information on how to contact you by electronic and paper mail. - - If the program does terminal interaction, make it output a short -notice like this when it starts in an interactive mode: - - Copyright (C) - This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. - This is free software, and you are welcome to redistribute it - under certain conditions; type `show c' for details. - -The hypothetical commands `show w' and `show c' should show the appropriate -parts of the General Public License. Of course, your program's commands -might be different; for a GUI interface, you would use an "about box". - - You should also get your employer (if you work as a programmer) or school, -if any, to sign a "copyright disclaimer" for the program, if necessary. -For more information on this, and how to apply and follow the GNU GPL, see -. - - The GNU General Public License does not permit incorporating your program -into proprietary programs. If your program is a subroutine library, you -may consider it more useful to permit linking proprietary applications with -the library. If this is what you want to do, use the GNU Lesser General -Public License instead of this License. But first, please read -. \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/graph_mod.hpp b/ct_core/include/ct/external/cppad/cg/graph_mod.hpp deleted file mode 100644 index 684377e75..000000000 --- a/ct_core/include/ct/external/cppad/cg/graph_mod.hpp +++ /dev/null @@ -1,92 +0,0 @@ -#ifndef CPPAD_CG_GRAPH_MOD_INCLUDED -#define CPPAD_CG_GRAPH_MOD_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -inline void CodeHandler::substituteIndependent(const CG& indep, - const CG& dep, - bool removeFromIndependents) { - substituteIndependent(*indep.getOperationNode(), *dep.getOperationNode(), removeFromIndependents); -} - -template -inline void CodeHandler::substituteIndependent(OperationNode& indep, - OperationNode& dep, - bool removeFromIndependents) { - using std::vector; - typedef CG CGBase; - - //check if the independent variable belongs to this handler - size_t indepIndex = getIndependentVariableIndex(indep); - - //check if the dependent variable belongs to this handler - size_t pos = dep.getHandlerPosition(); - if (pos >= _codeBlocks.size() || &dep != _codeBlocks[pos]) { - throw CGException("The dependent variable does not belong to this handler"); - } - - // determine the expression for the independent variable - CGBase dummyExp = solveFor(dep, indep); - - Argument arg; - // change the independent variable - if (dummyExp.isVariable()) { - arg = Argument (*dummyExp.getOperationNode()); - } else { - // create a bogus variable to avoid searching for all occurrences of the independent variable - arg = Argument (dummyExp.getValue()); - } - - indep.makeAlias(arg); - - if (removeFromIndependents) { - // remove the substituted variable from the independent variable vector - _independentVariables.erase(_independentVariables.begin() + indepIndex); - } -} - -template -inline void CodeHandler::undoSubstituteIndependent(OperationNode& indep) { - typename std::vector *>::const_iterator it = - std::find(_independentVariables.begin(), _independentVariables.end(), &indep); - if (it == _independentVariables.end()) { - throw CGException("Variable not found in the independent variable vector"); - } - - indep.setOperation(CGOpCode::Inv); -} - -template -inline void CodeHandler::removeIndependent(OperationNode& indep) { - if (indep.getOperationType() != CGOpCode::Alias) { - throw CGException("Cannot remove independent variable: not an alias"); - } - - typename std::vector *>::iterator it = - std::find(_independentVariables.begin(), _independentVariables.end(), &indep); - if (it == _independentVariables.end()) { - throw CGException("Variable not found in the independent variable vector"); - } - _independentVariables.erase(it); -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/identical.hpp b/ct_core/include/ct/external/cppad/cg/identical.hpp deleted file mode 100644 index e8f0b719e..000000000 --- a/ct_core/include/ct/external/cppad/cg/identical.hpp +++ /dev/null @@ -1,52 +0,0 @@ -#ifndef CPPAD_CG_IDENTICAL_INCLUDED -#define CPPAD_CG_IDENTICAL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { - -template -inline bool IdenticalPar(const CppAD::cg::CG& x) throw (CppAD::cg::CGException) { - if (!x.isParameter()) { - return false; // its value may change after tapping - } - return CppAD::IdenticalPar(x.getValue()); -} - -template -inline bool IdenticalZero(const CppAD::cg::CG& x) throw (CppAD::cg::CGException) { - if (!x.isParameter()) { - return false; // its value may change after tapping - } - return CppAD::IdenticalZero(x.getValue()); -} - -template -inline bool IdenticalOne(const CppAD::cg::CG& x) throw (CppAD::cg::CGException) { - if (!x.isParameter()) { - return false; // its value may change after tapping - } - return CppAD::IdenticalOne(x.getValue()); -} - -template -inline bool IdenticalEqualPar(const CppAD::cg::CG& x, - const CppAD::cg::CG& y) { - return x.isParameter() && y.isParameter() && CppAD::IdenticalEqualPar(x.getValue(), y.getValue()); -} - -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/job_timer.hpp b/ct_core/include/ct/external/cppad/cg/job_timer.hpp deleted file mode 100644 index 3f3431942..000000000 --- a/ct_core/include/ct/external/cppad/cg/job_timer.hpp +++ /dev/null @@ -1,337 +0,0 @@ -#ifndef CPPAD_CG_JOB_TIMER_INCLUDED -#define CPPAD_CG_JOB_TIMER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * A type of executing task - */ -class JobType { -private: - /** - * action name for the beginning of the task - */ - std::string _action; - /** - * action name for the completion of the task - */ - std::string _actionEnd; -public: - - inline JobType(const std::string& action, - const std::string& actionEnd) : - _action(action), - _actionEnd(actionEnd) { - } - - inline const std::string& getActionName() const { - return _action; - } - - inline void setActionName(const std::string& action) { - _action = action; - } - - inline const std::string& getActionEndName()const { - return _actionEnd; - } - - inline void setActionEndName(const std::string& actionEnd) { - _actionEnd = actionEnd; - } - - inline virtual ~JobType() { - } -}; - -/** - * Holds several job types - */ -template -class JobTypeHolder { -public: - static const JobType DEFAULT; - static const JobType LOOP_DETECTION; - static const JobType GRAPH; - static const JobType SOURCE_FOR_MODEL; - static const JobType SOURCE_GENERATION; - static const JobType COMPILING_FOR_MODEL; - static const JobType COMPILING; - static const JobType COMPILING_DYNAMIC_LIBRARY; - static const JobType DYNAMIC_MODEL_LIBRARY; - static const JobType STATIC_MODEL_LIBRARY; - static const JobType ASSEMBLE_STATIC_LIBRARY; - static const JobType JIT_MODEL_LIBRARY; -}; - -template -const JobType JobTypeHolder::DEFAULT("generating", "generated"); - -template -const JobType JobTypeHolder::LOOP_DETECTION("starting loop detection", "ended loop detection"); - -template -const JobType JobTypeHolder::GRAPH("creating operation graph for", "created operation graph for"); - -template -const JobType JobTypeHolder::SOURCE_FOR_MODEL("source-code for model", "source-code for model"); - -template -const JobType JobTypeHolder::SOURCE_GENERATION("generating source for", "generated source for"); - -template -const JobType JobTypeHolder::COMPILING_FOR_MODEL("compiling object files", "compiled object files"); - -template -const JobType JobTypeHolder::COMPILING("compiling", "compiled"); - -template -const JobType JobTypeHolder::COMPILING_DYNAMIC_LIBRARY("compiling dynamic library", "compiled library"); - -template -const JobType JobTypeHolder::DYNAMIC_MODEL_LIBRARY("creating library", "created library"); - -template -const JobType JobTypeHolder::STATIC_MODEL_LIBRARY("creating library", "created library"); - -template -const JobType JobTypeHolder::ASSEMBLE_STATIC_LIBRARY("assembling static library", "assembled static library"); - -template -const JobType JobTypeHolder::JIT_MODEL_LIBRARY("preparing JIT library", "prepared JIT library"); - -/** - * Represents a task for which the execution time will be determined - */ -class Job { -private: - /** - * type - */ - const JobType* _type; - /** - * Job name - */ - std::string _name; - /** - * Job starting time - */ - std::chrono::steady_clock::time_point _beginTime; - /** - * Whether or not there are/were other jobs inside - */ - bool _nestedJobs; -public: - - inline Job(const JobType& type, - const std::string& name) : - _type(&type), - _name(name), - _beginTime(std::chrono::steady_clock::now()), - _nestedJobs(false) { - } - - inline const JobType& getType()const { - return *_type; - } - - inline const std::string& name() const { - return _name; - } - - inline std::chrono::steady_clock::time_point beginTime() const { - return _beginTime; - } - - inline virtual ~Job() { - } - - friend class JobTimer; -}; - -/** - * A listener for job start/end events - */ -class JobListener { -public: - typedef std::chrono::steady_clock::duration duration; - - virtual void jobStarted(const std::vector& job) = 0; - - virtual void jobEndended(const std::vector& job, - duration elapsed) = 0; -}; - -/** - * Utility class used to print elapsed times of jobs - */ -class JobTimer : public JobTypeHolder<> { -protected: - /** - * Whether or not to print progress information to the standard - * output - */ - bool _verbose; -private: - /** - * saves the current job names - */ - std::vector _jobs; - /** - * - */ - size_t _maxLineWidth; - /** - * number of spaces per indentation level - */ - size_t _indent; - /** - * - */ - std::ostringstream _os; - /** - * - */ - std::string _action; - /** - * - */ - std::string _actionEnd; - /** - * - */ - std::set _listeners; -public: - - JobTimer() : - _verbose(false), - _maxLineWidth(80), - _indent(2) { - } - - inline bool isVerbose() const { - return _verbose; - } - - inline void setVerbose(bool verbose) { - _verbose = verbose; - } - - inline size_t getMaxLineWidth() const { - return _maxLineWidth; - } - - inline void setMaxLineWidth(size_t width) { - _maxLineWidth = width; - } - - /** - * Provides the number of currently running jobs - * - * @return the number of running jobs - */ - inline size_t getJobCount() const { - return _jobs.size(); - } - - inline void addListener(JobListener& l) { - _listeners.insert(&l); - } - - inline bool removeListener(JobListener& l) { - return _listeners.erase(&l) > 0; - } - - inline void startingJob(const std::string& jobName, - const JobType& type = JobTypeHolder<>::DEFAULT, - const std::string& prefix = "") { - - _jobs.push_back(Job(type, jobName)); - - if (_verbose) { - OStreamConfigRestore osr(std::cout); - - Job& job = _jobs.back(); - - size_t indent = 0; - if (_jobs.size() > 1) { - Job& parent = _jobs[_jobs.size() - 2]; // must be after adding job - if (!parent._nestedJobs) { - parent._nestedJobs = true; - std::cout << "\n"; - } - indent = _indent * (_jobs.size() - 1); - } - - _os.str(""); - if (indent > 0) _os << std::string(indent, ' '); - if (!prefix.empty()) _os << prefix << " "; - _os << type.getActionName() << " " << job.name() << " ..."; - - char f = std::cout.fill(); - std::cout << std::setw(_maxLineWidth) << std::setfill('.') << std::left << _os.str(); - std::cout.flush(); - std::cout.fill(f); // restore fill character - } - - // notify listeners - for (JobListener* l : _listeners) { - l->jobStarted(_jobs); - } - } - - inline void finishedJob() { - using namespace std::chrono; - - CPPADCG_ASSERT_UNKNOWN(_jobs.size() > 0); - - Job& job = _jobs.back(); - - std::chrono::steady_clock::duration elapsed = steady_clock::now() - job.beginTime(); - - if (_verbose) { - OStreamConfigRestore osr(std::cout); - - if (job._nestedJobs) { - _os.str(""); - if (!_jobs.empty()) - _os << std::string(_indent * (_jobs.size() - 1), ' '); - _os << job.getType().getActionEndName() << " " << job.name() << " ..."; - - char f = std::cout.fill(); - std::cout << std::setw(_maxLineWidth) << std::setfill('.') << std::left << _os.str(); - std::cout.fill(f); // restore fill character - } - - std::cout << " done [" << std::fixed << std::setprecision(3) << duration(elapsed).count() << "]" << std::endl; - } - - // notify listeners - for (JobListener* l : _listeners) { - l->jobEndended(_jobs, elapsed); - } - - _jobs.pop_back(); - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_atomic_fun.hpp b/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_atomic_fun.hpp deleted file mode 100644 index e91def5bb..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_atomic_fun.hpp +++ /dev/null @@ -1,75 +0,0 @@ -#ifndef CPPAD_CG_LANG_C_ATOMIC_FUN_INCLUDED -#define CPPAD_CG_LANG_C_ATOMIC_FUN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -extern "C" { - -/** - * A wrapper for an array. - * It is used to call forward and reverse functions of atomic functions in - * the generated C source-code. - */ -typedef struct Array { - /** - * Array values. For dense arrays its size is defined by - * ::size otherwise by ::nnz. - */ - void* data; - /** - * Total array size. - */ - unsigned long size; - /** - * Whether or not it is a sparse array. - */ - int sparse; - /** - * Indexes of sparse array (undefined for dense). - */ - const unsigned long* idx; - /** - * Number of non-zeros (size of data; undefined for dense). - */ - unsigned long nnz; -} Array; - -/** - * Holds function pointers that the compiled code uses to call atomic functions. - */ -struct LangCAtomicFun { - /** - * A pointer to the compiled model object (e.g. LinuxDynamicLibModel) - */ - void* libModel; - - int (*forward)(void* libModel, - int atomicIndex, - int q, - int p, - const Array tx[], - Array* ty); - - int (*reverse)(void* libModel, - int atomicIndex, - int p, - const Array tx[], - Array* px, - const Array py[]); -}; - -} - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_custom_var_name_gen.hpp b/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_custom_var_name_gen.hpp deleted file mode 100644 index d8567d599..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_custom_var_name_gen.hpp +++ /dev/null @@ -1,98 +0,0 @@ -#ifndef CPPAD_CG_LANG_C_CUSTOM_VAR_NAME_GEN_INCLUDED -#define CPPAD_CG_LANG_C_CUSTOM_VAR_NAME_GEN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Creates variables names for the source code using a list of provided - * custom names. - * - * @author Joao Leal - */ -template -class LangCCustomVariableNameGenerator : public LangCDefaultVariableNameGenerator { -protected: - // - const std::vector depNames_; - const std::vector indepNames_; -public: - - LangCCustomVariableNameGenerator(const std::vector& depNames, - const std::vector& indepNames, - const std::string& depName = "y", - const std::string& indepName = "x", - const std::string& tmpName = "v", - const std::string& tmpArrayName = "array") : - LangCDefaultVariableNameGenerator(depName, indepName, tmpName, tmpArrayName), - depNames_(depNames), - indepNames_(indepNames) { - } - - virtual std::string generateDependent(size_t index) override { - if (index < depNames_.size() && !depNames_[index].empty()) { - return depNames_[index]; - } else { - return LangCDefaultVariableNameGenerator::generateDependent(index); - } - } - - virtual std::string generateIndependent(const OperationNode& independent, - size_t id) override { - size_t index = id - 1; - if (index < indepNames_.size() && !indepNames_[index].empty()) { - return indepNames_[index]; - } else { - return LangCDefaultVariableNameGenerator::generateIndependent(independent, id); - } - } - - virtual bool isConsecutiveInIndepArray(const OperationNode& indepFirst, - size_t idFirst, - const OperationNode& indepSecond, - size_t idSecond) override { - size_t index1 = idFirst - 1; - size_t index2 = idSecond - 1; - - if ((index1 > indepNames_.size() || indepNames_[index1].empty()) && - (index2 > indepNames_.size() || indepNames_[index2].empty())) { - return index1 + 1 == index2; - } else { - return false; // individual names used (not elements of arrays) - } - } - - virtual bool isInSameIndependentArray(const OperationNode& indep1, - size_t id1, - const OperationNode& indep2, - size_t id2) override { - size_t index1 = id1 - 1; - size_t index2 = id2 - 1; - - return (index1 > indepNames_.size() || indepNames_[index1].empty()) && - (index2 > indepNames_.size() || indepNames_[index2].empty()); - } - - inline virtual ~LangCCustomVariableNameGenerator() { - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_default_hessian_var_name_gen.hpp b/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_default_hessian_var_name_gen.hpp deleted file mode 100644 index dfd943a11..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_default_hessian_var_name_gen.hpp +++ /dev/null @@ -1,250 +0,0 @@ -#ifndef CPPAD_CG_LANG_C_DEFAULT_HESSIAN_VAR_NAME_GEN_INCLUDED -#define CPPAD_CG_LANG_C_DEFAULT_HESSIAN_VAR_NAME_GEN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Creates variables names for the source code generated for Hessian - * calculations. - * The independent variables are considered to have been registered first as - * variable in the code generation handler and then the multipliers. - * - * @author Joao Leal - */ -template -class LangCDefaultHessianVarNameGenerator : public VariableNameGenerator { -protected: - VariableNameGenerator* _nameGen; - // the lowest variable ID used for the equation multipliers - const size_t _minMultiplierID; - // array name of the independent variables - const std::string _multName; - // auxiliary string stream - std::stringstream _ss; -public: - - LangCDefaultHessianVarNameGenerator(VariableNameGenerator* nameGen, - size_t n) : - _nameGen(nameGen), - _minMultiplierID(n + 1), - _multName("mult") { - - CPPADCG_ASSERT_KNOWN(_nameGen != nullptr, "The name generator must not be NULL"); - - initialize(); - } - - LangCDefaultHessianVarNameGenerator(VariableNameGenerator* nameGen, - const std::string& multName, - size_t n) : - _nameGen(nameGen), - _minMultiplierID(n + 1), - _multName(multName) { - - CPPADCG_ASSERT_KNOWN(_nameGen != nullptr, "The name generator must not be null"); - CPPADCG_ASSERT_KNOWN(_multName.size() > 0, "The name for the multipliers must not be empty"); - - initialize(); - } - - virtual const std::vector& getDependent() const override { - return _nameGen->getDependent(); - } - - virtual const std::vector& getTemporary() const override { - return _nameGen->getTemporary(); - } - - virtual size_t getMinTemporaryVariableID() const override { - return _nameGen->getMinTemporaryVariableID(); - } - - virtual size_t getMaxTemporaryVariableID() const override { - return _nameGen->getMaxTemporaryVariableID(); - } - - virtual size_t getMaxTemporaryArrayVariableID() const override { - return _nameGen->getMaxTemporaryArrayVariableID(); - } - - virtual size_t getMaxTemporarySparseArrayVariableID() const override { - return _nameGen->getMaxTemporarySparseArrayVariableID(); - } - - virtual std::string generateDependent(size_t index) override { - return _nameGen->generateDependent(index); - } - - virtual std::string generateIndependent(const OperationNode& independent, - size_t id) override { - if (id < _minMultiplierID) { - return _nameGen->generateIndependent(independent, id); - } - - _ss.clear(); - _ss.str(""); - _ss << _multName << "[" << (id - _minMultiplierID) << "]"; - return _ss.str(); - } - - virtual std::string generateTemporary(const OperationNode& variable, - size_t id) override { - return _nameGen->generateTemporary(variable, id); - } - - virtual std::string generateTemporaryArray(const OperationNode& variable, - size_t id) override { - return _nameGen->generateTemporaryArray(variable, id); - } - - virtual std::string generateTemporarySparseArray(const OperationNode& variable, - size_t id) override { - return _nameGen->generateTemporarySparseArray(variable, id); - } - - virtual std::string generateIndexedDependent(const OperationNode& var, - size_t id, - const IndexPattern& ip) override { - return _nameGen->generateIndexedDependent(var, id, ip); - } - - virtual std::string generateIndexedIndependent(const OperationNode& indexedIndep, - size_t id, - const IndexPattern& ip) override { - bool isX = indexedIndep.getInfo()[0] == 0; - if (isX) { - return _nameGen->generateIndexedIndependent(indexedIndep, id, ip); - } - - size_t nIndex = indexedIndep.getArguments().size(); - - CPPADCG_ASSERT_KNOWN(indexedIndep.getOperationType() == CGOpCode::LoopIndexedIndep, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(nIndex > 0, "Invalid number of arguments"); - - std::vector*> indices(nIndex); - for (size_t i = 0; i < nIndex; ++i) {// typically there is only one index but there may be more - CPPADCG_ASSERT_KNOWN(indexedIndep.getArguments()[i].getOperation() != nullptr, "Invalid argument"); - CPPADCG_ASSERT_KNOWN(indexedIndep.getArguments()[i].getOperation()->getOperationType() == CGOpCode::Index, "Invalid argument"); - indices[i] = &static_cast&> (*indexedIndep.getArguments()[i].getOperation()).getIndex(); - } - - _ss.clear(); - _ss.str(""); - - _ss << _multName << "[" << LanguageC::indexPattern2String(ip, indices) << "]"; - return _ss.str(); - } - - virtual const std::string& getIndependentArrayName(const OperationNode& indep, - size_t id) override { - if (id < _minMultiplierID) - return _nameGen->getIndependentArrayName(indep, id); - else - return _multName; - } - - virtual size_t getIndependentArrayIndex(const OperationNode& indep, - size_t id) override { - if (id < _minMultiplierID) - return _nameGen->getIndependentArrayIndex(indep, id); - else - return id - _minMultiplierID; - } - - virtual bool isConsecutiveInIndepArray(const OperationNode& indepFirst, - size_t id1, - const OperationNode& indepSecond, - size_t id2) override { - if ((id1 < _minMultiplierID) != (id2 < _minMultiplierID)) - return false; - - if (id1 < _minMultiplierID && id2 < _minMultiplierID) - return _nameGen->isConsecutiveInIndepArray(indepFirst, id1, indepSecond, id2); - else - return id1 + 1 == id2; - } - - virtual bool isInSameIndependentArray(const OperationNode& indep1, - size_t id1, - const OperationNode& indep2, - size_t id2) override { - size_t l1; - if (indep1.getOperationType() == CGOpCode::Inv) { - l1 = id1 < _minMultiplierID ? 0 : 1; - } else { - l1 = indep1.getInfo()[0]; //CGLoopIndexedIndepOp - } - - size_t l2; - if (indep2.getOperationType() == CGOpCode::Inv) { - l2 = id2 < _minMultiplierID ? 0 : 1; - } else { - l2 = indep2.getInfo()[0]; //CGLoopIndexedIndepOp - } - - return l1 == l2; - } - - virtual void setTemporaryVariableID(size_t minTempID, - size_t maxTempID, - size_t maxTempArrayID, - size_t maxTempSparseArrayID) override { - _nameGen->setTemporaryVariableID(minTempID, maxTempID, maxTempArrayID, maxTempSparseArrayID); - } - - virtual const std::string& getTemporaryVarArrayName(const OperationNode& var, - size_t id) override { - return _nameGen->getTemporaryVarArrayName(var, id); - } - - virtual size_t getTemporaryVarArrayIndex(const OperationNode& var, - size_t id) override { - return _nameGen->getTemporaryVarArrayIndex(var, id); - } - - virtual bool isConsecutiveInTemporaryVarArray(const OperationNode& varFirst, - size_t idFirst, - const OperationNode& varSecond, - size_t idSecond) override { - return _nameGen->isConsecutiveInTemporaryVarArray(varFirst, idFirst, varSecond, idSecond); - } - - virtual bool isInSameTemporaryVarArray(const OperationNode& var1, - size_t id1, - const OperationNode& var2, - size_t id2) override { - return _nameGen->isInSameTemporaryVarArray(var1, id1, var2, id2); - } - - inline virtual ~LangCDefaultHessianVarNameGenerator() { - } - -private: - - inline void initialize() { - this->_independent = _nameGen->getIndependent(); // copy - - this->_independent.push_back(FuncArgument(_multName)); - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_default_reverse2_var_name_gen.hpp b/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_default_reverse2_var_name_gen.hpp deleted file mode 100644 index 966179b15..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_default_reverse2_var_name_gen.hpp +++ /dev/null @@ -1,278 +0,0 @@ -#ifndef CPPAD_CG_LANG_C_DEFAULT_REVERSE2_VAR_NAME_GEN_INCLUDED -#define CPPAD_CG_LANG_C_DEFAULT_REVERSE2_VAR_NAME_GEN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Creates variables names for the source code generated for second-order - * reverse mode calculations. - * The independent variables are considered to have been registered first, - * followed by a first level of additional variables and then a second. - * - * @author Joao Leal - */ -template -class LangCDefaultReverse2VarNameGenerator : public VariableNameGenerator { -protected: - VariableNameGenerator* _nameGen; - // the lowest variable ID used for the first independent variable level - const size_t _minLevel1ID; - // array name of the independent variables (1st level) - const std::string _level1Name; - // the lowest variable ID used for the second independent variable level - const size_t _minLevel2ID; - // array name of the independent variables (2nd level) - const std::string _level2Name; - // auxiliary string stream - std::stringstream _ss; -public: - - LangCDefaultReverse2VarNameGenerator(VariableNameGenerator* nameGen, - size_t n, - size_t n1) : - _nameGen(nameGen), - _minLevel1ID(n + 1), - _level1Name("tx1"), - _minLevel2ID(_minLevel1ID + n1), - _level2Name("py2") { - - CPPADCG_ASSERT_KNOWN(_nameGen != nullptr, "The name generator must not be null"); - - initialize(); - } - - LangCDefaultReverse2VarNameGenerator(VariableNameGenerator* nameGen, - size_t n, - const std::string& level1Name, - size_t n1, - const std::string& level2Name) : - _nameGen(nameGen), - _minLevel1ID(n + 1), - _level1Name(level1Name), - _minLevel2ID(_minLevel1ID + n1), - _level2Name(level2Name) { - - CPPADCG_ASSERT_KNOWN(_nameGen != nullptr, "The name generator must not be null"); - CPPADCG_ASSERT_KNOWN(_level1Name.size() > 0, "The name for the first level must not be empty"); - CPPADCG_ASSERT_KNOWN(_level2Name.size() > 0, "The name for the second level must not be empty"); - - initialize(); - } - - virtual const std::vector& getDependent() const override { - return _nameGen->getDependent(); - } - - virtual const std::vector& getTemporary() const override { - return _nameGen->getTemporary(); - } - - virtual size_t getMinTemporaryVariableID() const override { - return _nameGen->getMinTemporaryVariableID(); - } - - virtual size_t getMaxTemporaryVariableID() const override { - return _nameGen->getMaxTemporaryVariableID(); - } - - virtual size_t getMaxTemporaryArrayVariableID() const override { - return _nameGen->getMaxTemporaryArrayVariableID(); - } - - virtual size_t getMaxTemporarySparseArrayVariableID() const override { - return _nameGen->getMaxTemporarySparseArrayVariableID(); - } - - virtual std::string generateDependent(size_t index) override { - return _nameGen->generateDependent(index); - } - - virtual std::string generateIndependent(const OperationNode& independent, - size_t id) override { - if (id < _minLevel1ID) { - return _nameGen->generateIndependent(independent, id); - } else { - _ss.clear(); - _ss.str(""); - if (id < _minLevel2ID) { - _ss << _level1Name << "[" << (id - _minLevel1ID) << "]"; - } else { - _ss << _level2Name << "[" << (id - _minLevel2ID) << "]"; - } - return _ss.str(); - } - } - - virtual std::string generateTemporary(const OperationNode& variable, - size_t id) override { - return _nameGen->generateTemporary(variable, id); - } - - virtual std::string generateTemporaryArray(const OperationNode& variable, - size_t id) override { - return _nameGen->generateTemporaryArray(variable, id); - } - - virtual std::string generateTemporarySparseArray(const OperationNode& variable, - size_t id) override { - return _nameGen->generateTemporarySparseArray(variable, id); - } - - virtual std::string generateIndexedDependent(const OperationNode& var, - size_t id, - const IndexPattern& ip) override { - return _nameGen->generateIndexedDependent(var, id, ip); - } - - virtual std::string generateIndexedIndependent(const OperationNode& independent, - size_t id, - const IndexPattern& ip) override { - size_t varType = independent.getInfo()[0]; - if (varType == 0) { - return _nameGen->generateIndexedIndependent(independent, id, ip); - } else { - size_t nIndex = independent.getArguments().size(); - - CPPADCG_ASSERT_KNOWN(independent.getOperationType() == CGOpCode::LoopIndexedIndep, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(nIndex > 0, "Invalid number of arguments"); - - _ss.clear(); - _ss.str(""); - - std::vector*> indices(nIndex); - for (size_t i = 0; i < nIndex; ++i) {// typically there is only one index but there may be more - CPPADCG_ASSERT_KNOWN(independent.getArguments()[i].getOperation() != nullptr, "Invalid argument"); - CPPADCG_ASSERT_KNOWN(independent.getArguments()[i].getOperation()->getOperationType() == CGOpCode::Index, "Invalid argument"); - indices[i] = &static_cast&> (*independent.getArguments()[i].getOperation()).getIndex(); - } - - if (varType == 1) { - _ss << _level1Name << "[" << LanguageC::indexPattern2String(ip, indices) << "]"; - } else { - _ss << _level2Name << "[" << LanguageC::indexPattern2String(ip, indices) << "]"; - } - return _ss.str(); - } - - } - - virtual const std::string& getIndependentArrayName(const OperationNode& indep, - size_t id) override { - if (id < _minLevel1ID) - return _nameGen->getIndependentArrayName(indep, id); - else if (id < _minLevel2ID) - return _level1Name; - else - return _level2Name; - } - - virtual size_t getIndependentArrayIndex(const OperationNode& indep, - size_t id) override { - if (id < _minLevel1ID) - return _nameGen->getIndependentArrayIndex(indep, id); - else if (id < _minLevel2ID) - return id - _minLevel1ID; - else - return id - _minLevel2ID; - } - - virtual bool isConsecutiveInIndepArray(const OperationNode& indepFirst, - size_t id1, - const OperationNode& indepSecond, - size_t id2) override { - if ((id1 < _minLevel1ID) != (id2 < _minLevel1ID)) - return false; - - if (id1 < _minLevel1ID && id2 < _minLevel1ID) - return _nameGen->isConsecutiveInIndepArray(indepFirst, id1, indepSecond, id2); - - if ((id1 < _minLevel2ID) != (id2 < _minLevel2ID)) - return false; - - return id1 + 1 == id2; - } - - virtual bool isInSameIndependentArray(const OperationNode& indep1, - size_t id1, - const OperationNode& indep2, - size_t id2) override { - size_t l1; - if (indep1.getOperationType() == CGOpCode::Inv) { - l1 = id1 < _minLevel1ID ? 0 : (id1 < _minLevel2ID ? 1 : 2); - } else { - l1 = indep1.getInfo()[0]; //CGLoopIndexedIndepOp - } - - size_t l2; - if (indep2.getOperationType() == CGOpCode::Inv) { - l2 = id2 < _minLevel1ID ? 0 : (id2 < _minLevel2ID ? 1 : 2); - } else { - l2 = indep2.getInfo()[0]; //CGLoopIndexedIndepOp - } - - return l1 == l2; - } - - virtual const std::string& getTemporaryVarArrayName(const OperationNode& var, - size_t id) override { - return _nameGen->getTemporaryVarArrayName(var, id); - } - - virtual size_t getTemporaryVarArrayIndex(const OperationNode& var, - size_t id) override { - return _nameGen->getTemporaryVarArrayIndex(var, id); - } - - virtual bool isConsecutiveInTemporaryVarArray(const OperationNode& varFirst, - size_t idFirst, - const OperationNode& varSecond, - size_t idSecond) override { - return _nameGen->isConsecutiveInTemporaryVarArray(varFirst, idFirst, varSecond, idSecond); - } - - virtual bool isInSameTemporaryVarArray(const OperationNode& var1, - size_t id1, - const OperationNode& var2, - size_t id2) override { - return _nameGen->isInSameTemporaryVarArray(var1, id1, var2, id2); - } - - virtual void setTemporaryVariableID(size_t minTempID, - size_t maxTempID, - size_t maxTempArrayID, - size_t maxTempSparseArrayID) override { - _nameGen->setTemporaryVariableID(minTempID, maxTempID, maxTempArrayID, maxTempSparseArrayID); - } - - inline virtual ~LangCDefaultReverse2VarNameGenerator() { - } - -private: - - inline void initialize() { - this->_independent = _nameGen->getIndependent(); // copy - this->_independent.push_back(FuncArgument(_level1Name)); - this->_independent.push_back(FuncArgument(_level2Name)); - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_default_var_name_gen.hpp b/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_default_var_name_gen.hpp deleted file mode 100644 index 3f6ccc5b3..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_default_var_name_gen.hpp +++ /dev/null @@ -1,260 +0,0 @@ -#ifndef CPPAD_CG_LANG_C_DEFAULT_VAR_NAME_GEN_INCLUDED -#define CPPAD_CG_LANG_C_DEFAULT_VAR_NAME_GEN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Creates variables names for the source code. - * - * @author Joao Leal - */ -template -class LangCDefaultVariableNameGenerator : public VariableNameGenerator { -protected: - // auxiliary string stream - std::stringstream _ss; - // array name of the dependent variables - std::string _depName; - // array name of the independent variables - std::string _indepName; - // array name of the temporary variables - std::string _tmpName; - // array name of the temporary array variables - std::string _tmpArrayName; - // sparse array name of the temporary array variables - std::string _tmpSparseArrayName; - // the lowest variable ID used for the temporary variables - size_t _minTemporaryID; - // the highest variable ID used for the temporary variables - size_t _maxTemporaryID; - // the highest ID used for the temporary array variables - size_t _maxTemporaryArrayID; - // the highest ID used for the temporary sparse array variables - size_t _maxTemporarySparseArrayID; -public: - - inline LangCDefaultVariableNameGenerator(const std::string& depName = "y", - const std::string& indepName = "x", - const std::string& tmpName = "v", - const std::string& tmpArrayName = "array", - const std::string& tmpSparseArrayName = "sarray") : - _depName(depName), - _indepName(indepName), - _tmpName(tmpName), - _tmpArrayName(tmpArrayName), - _tmpSparseArrayName(tmpSparseArrayName), - _minTemporaryID(0), // not really required (but it avoids warnings) - _maxTemporaryID(0), // not really required (but it avoids warnings) - _maxTemporaryArrayID(0), // not really required (but it avoids warnings) - _maxTemporarySparseArrayID(0) { // not really required (but it avoids warnings) - - this->_independent.push_back(FuncArgument(_indepName)); - this->_dependent.push_back(FuncArgument(_depName)); - this->_temporary.push_back(FuncArgument(_tmpName)); - this->_temporary.push_back(FuncArgument(_tmpArrayName)); - this->_temporary.push_back(FuncArgument(_tmpSparseArrayName)); - } - - inline virtual size_t getMinTemporaryVariableID() const override { - return _minTemporaryID; - } - - inline virtual size_t getMaxTemporaryVariableID() const override { - return _maxTemporaryID; - } - - inline virtual size_t getMaxTemporaryArrayVariableID() const override { - return _maxTemporaryArrayID; - } - - virtual size_t getMaxTemporarySparseArrayVariableID() const override { - return _maxTemporarySparseArrayID; - } - - inline virtual std::string generateDependent(size_t index) override { - _ss.clear(); - _ss.str(""); - - _ss << _depName << "[" << index << "]"; - - return _ss.str(); - } - - inline virtual std::string generateIndependent(const OperationNode& independent, - size_t id) override { - _ss.clear(); - _ss.str(""); - - _ss << _indepName << "[" << (id - 1) << "]"; - - return _ss.str(); - } - - inline virtual std::string generateTemporary(const OperationNode& variable, - size_t id) override { - _ss.clear(); - _ss.str(""); - - if (this->_temporary[0].array) { - _ss << _tmpName << "[" << (id - this->_minTemporaryID) << "]"; - } else { - _ss << _tmpName << id; - } - - return _ss.str(); - } - - virtual std::string generateTemporaryArray(const OperationNode& variable, - size_t id) override { - _ss.clear(); - _ss.str(""); - - CPPADCG_ASSERT_UNKNOWN(variable.getOperationType() == CGOpCode::ArrayCreation); - - _ss << "&" << _tmpArrayName << "[" << (id - 1) << "]"; - - return _ss.str(); - } - - virtual std::string generateTemporarySparseArray(const OperationNode& variable, - size_t id) override { - _ss.clear(); - _ss.str(""); - - CPPADCG_ASSERT_UNKNOWN(variable.getOperationType() == CGOpCode::SparseArrayCreation); - - _ss << "&" << _tmpSparseArrayName << "[" << (id - 1) << "]"; - - return _ss.str(); - } - - virtual std::string generateIndexedDependent(const OperationNode& var, - size_t id, - const IndexPattern& ip) override { - CPPADCG_ASSERT_KNOWN(var.getOperationType() == CGOpCode::LoopIndexedDep, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(!var.getArguments().empty(), "Invalid number of arguments"); - - _ss.clear(); - _ss.str(""); - - _ss << _depName << "[" << LanguageC::indexPattern2String(ip, getIndexes(var, 1)) << "]"; - - return _ss.str(); - } - - virtual std::string generateIndexedIndependent(const OperationNode& independent, - size_t id, - const IndexPattern& ip) override { - CPPADCG_ASSERT_KNOWN(independent.getOperationType() == CGOpCode::LoopIndexedIndep, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(independent.getArguments().size() > 0, "Invalid number of arguments"); - - _ss.clear(); - _ss.str(""); - - _ss << _indepName << "[" << LanguageC::indexPattern2String(ip, getIndexes(independent, 0)) << "]"; - - return _ss.str(); - } - - inline virtual void setTemporaryVariableID(size_t minTempID, - size_t maxTempID, - size_t maxTempArrayID, - size_t maxTempSparseArrayID) override { - _minTemporaryID = minTempID; - _maxTemporaryID = maxTempID; - _maxTemporaryArrayID = maxTempArrayID; - _maxTemporarySparseArrayID = maxTempSparseArrayID; - - // if - // _minTemporaryID == _maxTemporaryID + 1 - // then no temporary variables are being used - CPPADCG_ASSERT_UNKNOWN(_minTemporaryID <= _maxTemporaryID + 1); - } - - virtual const std::string& getIndependentArrayName(const OperationNode& indep, - size_t id) override { - return _indepName; - } - - virtual size_t getIndependentArrayIndex(const OperationNode& indep, - size_t id) override { - return id - 1; - } - - virtual bool isConsecutiveInIndepArray(const OperationNode& indepFirst, - size_t idFirst, - const OperationNode& indepSecond, - size_t idSecond) override { - return idFirst + 1 == idSecond; - } - - virtual bool isInSameIndependentArray(const OperationNode& indep1, - size_t id1, - const OperationNode& indep2, - size_t id2) override { - return true; - } - - virtual const std::string& getTemporaryVarArrayName(const OperationNode& var, - size_t id) override { - return _tmpName; - } - - virtual size_t getTemporaryVarArrayIndex(const OperationNode& var, - size_t id) override { - return id - this->_minTemporaryID; - } - - virtual bool isConsecutiveInTemporaryVarArray(const OperationNode& varFirst, - size_t idFirst, - const OperationNode& varSecond, - size_t idSecond) override { - return idFirst + 1 == idSecond; - } - - virtual bool isInSameTemporaryVarArray(const OperationNode& var1, - size_t id1, - const OperationNode& var2, - size_t id2) override { - return true; - } - - inline virtual ~LangCDefaultVariableNameGenerator() { - } -protected: - - static inline std::vector*> getIndexes(const OperationNode& var, - size_t offset) { - const std::vector >& args = var.getArguments(); - std::vector*> indexes(args.size() - offset); - - for (size_t a = offset; a < args.size(); a++) { - CPPADCG_ASSERT_KNOWN(args[a].getOperation() != nullptr, "Invalid argument"); - CPPADCG_ASSERT_KNOWN(args[a].getOperation()->getOperationType() == CGOpCode::Index, "Invalid argument"); - - indexes[a - offset] = &static_cast*> (args[a].getOperation())->getIndex(); - } - - return indexes; - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_util.hpp b/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_util.hpp deleted file mode 100644 index 44b9f74f1..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/c/lang_c_util.hpp +++ /dev/null @@ -1,102 +0,0 @@ -#ifndef CPPAD_CG_LANG_C_UTIL_INCLUDED -#define CPPAD_CG_LANG_C_UTIL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Prints the model to standard output - * - * @param fun the model - */ -template -inline void printModel(ADFun >& fun) { - std::vector depNames; - std::vector indepNames; - printModel(fun, depNames, indepNames); -} - -/** - * Prints the model to standard output - * - * @param fun the model - * @param depNames the names to be used for the dependent variables - * @param indepNames the names to be used for the independent variables - */ -template -inline void printModel(ADFun >& fun, - const std::vector& depNames, - const std::vector& indepNames) { - CPPADCG_ASSERT_UNKNOWN(depNames.size() <= fun.Range()); - CPPADCG_ASSERT_UNKNOWN(indepNames.size() <= fun.Domain()); - - CodeHandler handler; - - std::vector > indep0(fun.Domain()); - handler.makeVariables(indep0); - - std::vector > dep0 = fun.Forward(0, indep0); - - LanguageC langC("double"); - - /** - * generate the source code - */ - LangCCustomVariableNameGenerator nameGen(depNames, indepNames, - "y", "x", "z", "array"); - - std::ostringstream code; - handler.generateCode(code, langC, dep0, nameGen); - std::cout << "\n" << code.str() << std::endl; -} - -/** - * Prints the model resulting in a single dependent variable. - */ -template -inline void printExpression(const CG& dep, - std::ostream& out = std::cout) { - if(dep.getOperationNode() != nullptr) { - if(dep.getOperationNode()->getCodeHandler() == nullptr) { - throw CGException("Unable to print expression: found an operation node without a CodeHandler!"); - } - - CodeHandler& handler = *dep.getOperationNode()->getCodeHandler(); - LanguageC langC("double"); - LangCDefaultVariableNameGenerator nameGen; - - std::vector > depv(1); - depv[0] = dep; - - std::ostringstream code; - handler.generateCode(code, langC, depv, nameGen); - out << code.str(); - } else { - out << "y[0] = " << dep.getValue() << ";" << std::endl; - } -} - -template -inline void printExpression(OperationNode& dep, - std::ostream& out = std::cout) { - printExpression(CG(dep), out); -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/c/language_c.hpp b/ct_core/include/ct/external/cppad/cg/lang/c/language_c.hpp deleted file mode 100644 index a5d212b42..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/c/language_c.hpp +++ /dev/null @@ -1,2095 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_C_INCLUDED -#define CPPAD_CG_LANGUAGE_C_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#define CPPAD_CG_C_LANG_FUNCNAME(fn) \ -inline virtual const std::string& fn ## FuncName() {\ - static const std::string name(#fn);\ - return name;\ -} - -namespace CppAD { -namespace cg { - -/** - * Generates code for the C language - * - * @author Joao Leal - */ -template -class LanguageC : public Language { -public: - typedef OperationNode Node; - typedef Argument Arg; -public: - static const std::string U_INDEX_TYPE; - static const std::string ATOMICFUN_STRUCT_DEFINITION; -protected: - static const std::string _C_COMP_OP_LT; - static const std::string _C_COMP_OP_LE; - static const std::string _C_COMP_OP_EQ; - static const std::string _C_COMP_OP_GE; - static const std::string _C_COMP_OP_GT; - static const std::string _C_COMP_OP_NE; - static const std::string _C_STATIC_INDEX_ARRAY; - static const std::string _C_SPARSE_INDEX_ARRAY; - static const std::string _ATOMIC_TX; - static const std::string _ATOMIC_TY; - static const std::string _ATOMIC_PX; - static const std::string _ATOMIC_PY; -private: - class AtomicFuncArray; //forward declaration -protected: - // the type name of the Base class (e.g. "double") - const std::string _baseTypeName; - // spaces for 1 level indentation - const std::string _spaces; - // information from the code handler (not owned) - LanguageGenerationData* _info; - // current indentation - std::string _indentation; - // variable name used for the inlet variable - std::string _inArgName; - // variable name used for the outlet variable - std::string _outArgName; - // variable name used for the atomic functions array - std::string _atomicArgName; - // output stream for the generated source code - std::ostringstream _code; - // creates the variable names - VariableNameGenerator* _nameGen; - // auxiliary string stream - std::ostringstream _ss; - // - size_t _independentSize; - // - size_t _minTemporaryVarID; - // maps the variable IDs to the their position in the dependent vector - // (some IDs may be the same as the independent variables when dep = indep) - std::map _dependentIDs; - // the dependent variable vector - const ArrayWrapper >* _dependent; - // the temporary variables that may require a declaration - std::map _temporary; - // the operator used for assignment of dependent variables - std::string _depAssignOperation; - // whether or not to ignore assignment of constant zero values to dependent variables - bool _ignoreZeroDepAssign; - // the name of the function to be created (if the string is empty no function is created) - std::string _functionName; - // the arguments provided to local functions called by the main function - std::string _localFunctionArguments; - // the maximum number of assignment (~lines) per local function - size_t _maxAssigmentsPerFunction; - // - std::map* _sources; - // the values in the temporary array - std::vector _tmpArrayValues; - // the values in the temporary sparse array - std::vector _tmpSparseArrayValues; - // the current state of Array structures used by atomic functions - std::map _atomicFuncArrays; - // indexes defined as function arguments - std::vector _funcArgIndexes; - std::vector*> _currentLoops; - // the maximum precision used to print values - size_t _parameterPrecision; -private: - std::string funcArgDcl_; - std::string localFuncArgDcl_; - std::string localFuncArgs_; - std::string auxArrayName_; - -public: - - /** - * Creates a C language source code generator - * - * @param varTypeName variable data type (e.g. double) - * @param spaces number of spaces for indentations - */ - LanguageC(const std::string& varTypeName, - size_t spaces = 3) : - _baseTypeName(varTypeName), - _spaces(spaces, ' '), - _info(nullptr), - _inArgName("in"), - _outArgName("out"), - _atomicArgName("atomicFun"), - _nameGen(nullptr), - _independentSize(0), // not really required (but it avoids warnings) - _minTemporaryVarID(0), // not really required (but it avoids warnings) - _dependent(nullptr), - _depAssignOperation("="), - _ignoreZeroDepAssign(false), - _maxAssigmentsPerFunction(0), - _sources(nullptr), - _parameterPrecision(std::numeric_limits::digits10) { - } - - inline const std::string& getArgumentIn() const { - return _inArgName; - } - - inline void setArgumentIn(const std::string& inArgName) { - _inArgName = inArgName; - } - - inline const std::string& getArgumentOut() const { - return _outArgName; - } - - inline void setArgumentOut(const std::string& outArgName) { - _outArgName = outArgName; - } - - inline const std::string& getArgumentAtomic() const { - return _atomicArgName; - } - - inline void setArgumentAtomic(const std::string& atomicArgName) { - _atomicArgName = atomicArgName; - } - - inline const std::string& getDependentAssignOperation() const { - return _depAssignOperation; - } - - inline void setDependentAssignOperation(const std::string& depAssignOperation) { - _depAssignOperation = depAssignOperation; - } - - inline bool isIgnoreZeroDepAssign() const { - return _ignoreZeroDepAssign; - } - - inline void setIgnoreZeroDepAssign(bool ignore) { - _ignoreZeroDepAssign = ignore; - } - - virtual void setGenerateFunction(const std::string& functionName) { - _functionName = functionName; - } - - virtual void setFunctionIndexArgument(const Node& funcArgIndex) { - _funcArgIndexes.resize(1); - _funcArgIndexes[0] = &funcArgIndex; - } - - virtual void setFunctionIndexArguments(const std::vector& funcArgIndexes) { - _funcArgIndexes = funcArgIndexes; - } - - virtual const std::vector& getFunctionIndexArguments() const { - return _funcArgIndexes; - } - - /** - * Provides the maximum precision used to print constant values in the - * generated source code - * - * @return the maximum number of digits - */ - virtual size_t getParameterPrecision() const { - return _parameterPrecision; - } - - /** - * Defines the maximum precision used to print constant values in the - * generated source code - * - * @param p the maximum number of digits - */ - virtual void setParameterPrecision(size_t p) { - _parameterPrecision = p; - } - - virtual void setMaxAssigmentsPerFunction(size_t maxAssigmentsPerFunction, - std::map* sources) { - _maxAssigmentsPerFunction = maxAssigmentsPerFunction; - _sources = sources; - } - - inline std::string generateTemporaryVariableDeclaration(bool isWrapperFunction, - bool zeroArrayDependents, - const std::vector& atomicMaxForward, - const std::vector& atomicMaxReverse) { - int maxForward = -1; - if (!atomicMaxForward.empty()) - maxForward = *std::max_element(atomicMaxForward.begin(), atomicMaxForward.end()); - - int maxReverse = -1; - if (!atomicMaxReverse.empty()) - maxReverse = *std::max_element(atomicMaxReverse.begin(), atomicMaxReverse.end()); - - return generateTemporaryVariableDeclaration(isWrapperFunction, zeroArrayDependents, - maxForward, maxReverse); - } - - /** - * Declares temporary variables used by a function. - * - * @param isWrapperFunction true if the declarations are for a wrapper - * function which calls other functions - * where the actual work is performed - * @param zeroArrayDependents whether or not the dependent variables - * should be set to zero before executing - * the operation graph - * @param maxForwardOrder the maximum order of forward mode calls to - * atomic functions - * @param maxReverseOrder the maximum order of reverse mode calls to - * atomic functions - * @return the string with the declarations for the temporary variables - */ - virtual std::string generateTemporaryVariableDeclaration(bool isWrapperFunction = false, - bool zeroArrayDependents = false, - int maxForwardOrder = -1, - int maxReverseOrder = -1) { - CPPADCG_ASSERT_UNKNOWN(_nameGen != nullptr); - - // declare variables - const std::vector& tmpArg = _nameGen->getTemporary(); - - CPPADCG_ASSERT_KNOWN(tmpArg.size() == 3, - "There must be two temporary variables"); - - _ss << _spaces << "// auxiliary variables\n"; - /** - * temporary variables - */ - if (tmpArg[0].array) { - size_t size = _nameGen->getMaxTemporaryVariableID() + 1 - _nameGen->getMinTemporaryVariableID(); - if (size > 0 || isWrapperFunction) { - _ss << _spaces << _baseTypeName << " " << tmpArg[0].name << "[" << size << "];\n"; - } - } else if (_temporary.size() > 0) { - for (const std::pair& p : _temporary) { - Node* var = p.second; - if (var->getName() == nullptr) { - var->setName(_nameGen->generateTemporary(*var, getVariableID(*var))); - } - } - - Node* var1 = _temporary.begin()->second; - const std::string& varName1 = *var1->getName(); - _ss << _spaces << _baseTypeName << " " << varName1; - - typename std::map::const_iterator it = _temporary.begin(); - for (it++; it != _temporary.end(); ++it) { - _ss << ", " << *it->second->getName(); - } - _ss << ";\n"; - } - - /** - * temporary array variables - */ - size_t arraySize = _nameGen->getMaxTemporaryArrayVariableID(); - if (arraySize > 0 || isWrapperFunction) { - _ss << _spaces << _baseTypeName << " " << tmpArg[1].name << "[" << arraySize << "];\n"; - } - - /** - * temporary sparse array variables - */ - size_t sArraySize = _nameGen->getMaxTemporarySparseArrayVariableID(); - if (sArraySize > 0 || isWrapperFunction) { - _ss << _spaces << _baseTypeName << " " << tmpArg[2].name << "[" << sArraySize << "];\n"; - _ss << _spaces << U_INDEX_TYPE << " " << _C_SPARSE_INDEX_ARRAY << "[" << sArraySize << "];\n"; - } - - if (!isWrapperFunction) { - generateArrayContainersDeclaration(_ss, maxForwardOrder, maxReverseOrder); - } - - // - if (!isWrapperFunction && (arraySize > 0 || sArraySize > 0)) { - _ss << _spaces << _baseTypeName << "* " << auxArrayName_ << ";\n"; - } - - if ((isWrapperFunction && zeroArrayDependents) || - (!isWrapperFunction && (arraySize > 0 || sArraySize > 0 || zeroArrayDependents))) { - _ss << _spaces << U_INDEX_TYPE << " i;\n"; - } - - // loop indexes - createIndexDeclaration(); - - // clean-up - std::string code = _ss.str(); - _ss.str(""); - - return code; - } - - inline void generateArrayContainersDeclaration(std::ostringstream& ss, - const std::vector& atomicMaxForward, - const std::vector& atomicMaxReverse) { - int maxForward = -1; - if (!atomicMaxForward.empty()) - maxForward = *std::max_element(atomicMaxForward.begin(), atomicMaxForward.end()); - - int maxReverse = -1; - if (!atomicMaxReverse.empty()) - maxReverse = *std::max_element(atomicMaxReverse.begin(), atomicMaxReverse.end()); - - generateArrayContainersDeclaration(ss, maxForward, maxReverse); - } - - virtual void generateArrayContainersDeclaration(std::ostringstream& ss, - int maxForwardOrder = -1, - int maxReverseOrder = -1) { - if (maxForwardOrder >= 0 || maxReverseOrder >= 0) { - ss << _spaces << "Array " << _ATOMIC_TX << "[" << (std::max(maxForwardOrder, maxReverseOrder) + 1) << "];\n"; - if (maxForwardOrder >= 0) - ss << _spaces << "Array " << _ATOMIC_TY << ";\n"; - if (maxReverseOrder >= 0) { - ss << _spaces << "Array " << _ATOMIC_PX << ";\n"; - ss << _spaces << "Array " << _ATOMIC_PY << "[" << (maxReverseOrder + 1) << "];\n"; - } - } - } - - virtual std::string generateDependentVariableDeclaration() { - const std::vector& depArg = _nameGen->getDependent(); - CPPADCG_ASSERT_KNOWN(depArg.size() > 0, - "There must be at least one dependent argument"); - - _ss << _spaces << "//dependent variables\n"; - for (size_t i = 0; i < depArg.size(); i++) { - _ss << _spaces << argumentDeclaration(depArg[i]) << " = " << _outArgName << "[" << i << "];\n"; - } - - std::string code = _ss.str(); - _ss.str(""); - return code; - } - - virtual std::string generateIndependentVariableDeclaration() { - const std::vector& indArg = _nameGen->getIndependent(); - CPPADCG_ASSERT_KNOWN(indArg.size() > 0, - "There must be at least one independent argument"); - - _ss << _spaces << "//independent variables\n"; - for (size_t i = 0; i < indArg.size(); i++) { - _ss << _spaces << "const " << argumentDeclaration(indArg[i]) << " = " << _inArgName << "[" << i << "];\n"; - } - - std::string code = _ss.str(); - _ss.str(""); - return code; - } - - inline std::string generateArgumentAtomicDcl() const { - return "struct LangCAtomicFun " + _atomicArgName; - } - - virtual std::string generateFunctionArgumentsDcl() const { - std::string args = generateFunctionIndexArgumentsDcl(); - if (!args.empty()) - args += ", "; - args += generateDefaultFunctionArgumentsDcl(); - - return args; - } - - virtual std::string generateDefaultFunctionArgumentsDcl() const { - return _baseTypeName + " const *const * " + _inArgName + - ", " + _baseTypeName + "*const * " + _outArgName + - ", " + generateArgumentAtomicDcl(); - } - - virtual std::string generateFunctionIndexArgumentsDcl() const { - std::string argtxt; - for (size_t a = 0; a < _funcArgIndexes.size(); a++) { - if (a > 0) argtxt += ", "; - argtxt += U_INDEX_TYPE + " " + *_funcArgIndexes[a]->getName(); - } - return argtxt; - } - - virtual std::string generateDefaultFunctionArguments() const { - return _inArgName + ", " + _outArgName + ", " + _atomicArgName; - } - - virtual std::string generateFunctionIndexArguments() const { - std::string argtxt; - for (size_t a = 0; a < _funcArgIndexes.size(); a++) { - if (a > 0) argtxt += ", "; - argtxt += *_funcArgIndexes[a]->getName(); - } - return argtxt; - } - - inline void createIndexDeclaration(); - - CPPAD_CG_C_LANG_FUNCNAME(abs) - CPPAD_CG_C_LANG_FUNCNAME(acos) - CPPAD_CG_C_LANG_FUNCNAME(asin) - CPPAD_CG_C_LANG_FUNCNAME(atan) - CPPAD_CG_C_LANG_FUNCNAME(cosh) - CPPAD_CG_C_LANG_FUNCNAME(cos) - CPPAD_CG_C_LANG_FUNCNAME(exp) - CPPAD_CG_C_LANG_FUNCNAME(log) - CPPAD_CG_C_LANG_FUNCNAME(sinh) - CPPAD_CG_C_LANG_FUNCNAME(sin) - CPPAD_CG_C_LANG_FUNCNAME(sqrt) - CPPAD_CG_C_LANG_FUNCNAME(tanh) - CPPAD_CG_C_LANG_FUNCNAME(tan) - CPPAD_CG_C_LANG_FUNCNAME(pow) - -#if CPPAD_USE_CPLUSPLUS_2011 - CPPAD_CG_C_LANG_FUNCNAME(erf) - CPPAD_CG_C_LANG_FUNCNAME(asinh) - CPPAD_CG_C_LANG_FUNCNAME(acosh) - CPPAD_CG_C_LANG_FUNCNAME(atanh) - CPPAD_CG_C_LANG_FUNCNAME(expm1) - CPPAD_CG_C_LANG_FUNCNAME(log1p) -#endif - - inline virtual ~LanguageC() { - } - - static inline void printIndexCondExpr(std::ostringstream& out, - const std::vector& info, - const std::string& index) { - CPPADCG_ASSERT_KNOWN(info.size() > 1 && info.size() % 2 == 0, "Invalid number of information elements for an index condition expression operation"); - - size_t infoSize = info.size(); - for (size_t e = 0; e < infoSize; e += 2) { - if (e > 0) { - out << " || "; - } - size_t min = info[e]; - size_t max = info[e + 1]; - if (min == max) { - out << index << " == " << min; - } else if (min == 0) { - out << index << " <= " << max; - } else if (max == std::numeric_limits::max()) { - out << min << " <= " << index; - } else { - if (infoSize != 2) - out << "("; - - if (max - min == 1) - out << min << " == " << index << " || " << index << " == " << max; - else - out << min << " <= " << index << " && " << index << " <= " << max; - - if (infoSize != 2) - out << ")"; - } - } - } - - /*********************************************************************** - * - **********************************************************************/ - - static inline void printStaticIndexArray(std::ostringstream& os, - const std::string& name, - const std::vector& values); - - static inline void printStaticIndexMatrix(std::ostringstream& os, - const std::string& name, - const std::map >& values); - - /*********************************************************************** - * index patterns - **********************************************************************/ - static inline void generateNames4RandomIndexPatterns(const std::set& randomPatterns); - - static inline void printRandomIndexPatternDeclaration(std::ostringstream& os, - const std::string& identation, - const std::set& randomPatterns); - - static inline std::string indexPattern2String(const IndexPattern& ip, - const Node& index); - - static inline std::string indexPattern2String(const IndexPattern& ip, - const std::string& index); - - static inline std::string indexPattern2String(const IndexPattern& ip, - const std::vector& indexes); - - static inline std::string indexPattern2String(const IndexPattern& ip, - const std::vector& indexes); - - static inline std::string linearIndexPattern2String(const LinearIndexPattern& lip, - const Node& index); - - static inline std::string linearIndexPattern2String(const LinearIndexPattern& lip, - const std::string& index); - - static inline bool isOffsetBy(const IndexPattern* ip, - const IndexPattern* refIp, - long offset); - - static inline bool isOffsetBy(const LinearIndexPattern* lIp, - const LinearIndexPattern* refLIp, - long offset); - - static inline bool isOffsetBy(const LinearIndexPattern& lIp, - const LinearIndexPattern& refLIp, - long offset); - - - static inline bool isOffsetBy(const SectionedIndexPattern* sIp, - const SectionedIndexPattern* refSecp, - long offset); - - static inline bool isOffsetBy(const SectionedIndexPattern& lIp, - const SectionedIndexPattern& refSecp, - long offset); - - static inline Plane2DIndexPattern* encapsulateIndexPattern(const LinearIndexPattern& refLIp, - size_t starti); - - static inline Plane2DIndexPattern* encapsulateIndexPattern(const SectionedIndexPattern& refSecp, - size_t starti); -protected: - - virtual void generateSourceCode(std::ostream& out, - const std::unique_ptr >& info) override { - - const bool createFunction = !_functionName.empty(); - const bool multiFunction = createFunction && _maxAssigmentsPerFunction > 0 && _sources != nullptr; - - // clean up - _code.str(""); - _ss.str(""); - _temporary.clear(); - _indentation = _spaces; - funcArgDcl_ = ""; - localFuncArgDcl_ = ""; - localFuncArgs_ = ""; - auxArrayName_ = ""; - _currentLoops.clear(); - _atomicFuncArrays.clear(); - - // save some info - _info = info.get(); - _independentSize = info->independent.size(); - _dependent = &info->dependent; - _nameGen = &info->nameGen; - _minTemporaryVarID = info->minTemporaryVarID; - const ArrayWrapper >& dependent = info->dependent; - const std::vector& variableOrder = info->variableOrder; - - _tmpArrayValues.resize(_nameGen->getMaxTemporaryArrayVariableID()); - std::fill(_tmpArrayValues.begin(), _tmpArrayValues.end(), nullptr); - _tmpSparseArrayValues.resize(_nameGen->getMaxTemporarySparseArrayVariableID()); - std::fill(_tmpSparseArrayValues.begin(), _tmpSparseArrayValues.end(), nullptr); - - /** - * generate index array names (might be used for variable names) - */ - generateNames4RandomIndexPatterns(info->indexRandomPatterns); - - /** - * generate variable names - */ - //generate names for the independent variables - for (size_t j = 0; j < _independentSize; j++) { - Node& op = *info->independent[j]; - if (op.getName() == nullptr) { - op.setName(_nameGen->generateIndependent(op, getVariableID(op))); - } - } - - // generate names for the dependent variables (must be after naming independents) - for (size_t i = 0; i < dependent.size(); i++) { - Node* node = dependent[i].getOperationNode(); - if (node != nullptr && node->getOperationType() != CGOpCode::LoopEnd && node->getName() == nullptr) { - if (node->getOperationType() == CGOpCode::LoopIndexedDep) { - size_t pos = node->getInfo()[0]; - const IndexPattern* ip = info->loopDependentIndexPatterns[pos]; - node->setName(_nameGen->generateIndexedDependent(*node, getVariableID(*node), *ip)); - - } else { - node->setName(_nameGen->generateDependent(i)); - } - } - } - - /** - * function variable declaration - */ - const std::vector& indArg = _nameGen->getIndependent(); - const std::vector& depArg = _nameGen->getDependent(); - const std::vector& tmpArg = _nameGen->getTemporary(); - CPPADCG_ASSERT_KNOWN(indArg.size() > 0 && depArg.size() > 0, - "There must be at least one dependent and one independent argument"); - CPPADCG_ASSERT_KNOWN(tmpArg.size() == 3, - "There must be three temporary variables"); - - if (createFunction) { - funcArgDcl_ = generateFunctionArgumentsDcl(); - localFuncArgDcl_ = funcArgDcl_ + ", " - + argumentDeclaration(tmpArg[0]) + ", " - + argumentDeclaration(tmpArg[1]) + ", " - + argumentDeclaration(tmpArg[2]) + ", " - + U_INDEX_TYPE + "* " + _C_SPARSE_INDEX_ARRAY; - localFuncArgs_ = generateDefaultFunctionArguments() + ", " - + tmpArg[0].name + ", " - + tmpArg[1].name + ", " - + tmpArg[2].name + ", " - + _C_SPARSE_INDEX_ARRAY; - } - - auxArrayName_ = tmpArg[1].name + "p"; - - /** - * Determine the dependent variables that result from the same operations - */ - // dependent variables indexes that are copies of other dependent variables - std::set dependentDuplicates; - - for (size_t i = 0; i < dependent.size(); i++) { - Node* node = dependent[i].getOperationNode(); - if (node != nullptr) { - CGOpCode type = node->getOperationType(); - if (type != CGOpCode::Inv && type != CGOpCode::LoopEnd) { - size_t varID = getVariableID(*node); - if (varID > 0) { - std::map::const_iterator it2 = _dependentIDs.find(varID); - if (it2 == _dependentIDs.end()) { - _dependentIDs[getVariableID(*node)] = i; - } else { - // there can be several dependent variables with the same ID - dependentDuplicates.insert(i); - } - } - } - } - } - - // the names of local functions - std::vector localFuncNames; - if (multiFunction) { - localFuncNames.reserve(variableOrder.size() / _maxAssigmentsPerFunction); - } - - /** - * non-constant variables - */ - if (variableOrder.size() > 0) { - // generate names for temporary variables - for (Node* node : variableOrder) { - CGOpCode op = node->getOperationType(); - if (!isDependent(*node) && op != CGOpCode::IndexDeclaration) { - // variable names for temporaries must always be created since they might have been used before with a different name/id - if (requiresVariableName(*node) && op != CGOpCode::ArrayCreation && op != CGOpCode::SparseArrayCreation) { - node->setName(_nameGen->generateTemporary(*node, getVariableID(*node))); - } else if (op == CGOpCode::ArrayCreation) { - node->setName(_nameGen->generateTemporaryArray(*node, getVariableID(*node))); - } else if (op == CGOpCode::SparseArrayCreation) { - node->setName(_nameGen->generateTemporarySparseArray(*node, getVariableID(*node))); - } - } - } - - /** - * Source code generation magic! - */ - if (info->zeroDependents) { - // zero initial values - const std::vector& depArg = _nameGen->getDependent(); - for (size_t i = 0; i < depArg.size(); i++) { - const FuncArgument& a = depArg[i]; - if (a.array) { - _code << _indentation << "for(i = 0; i < " << _dependent->size() << "; i++) " << a.name << "[i]"; - } else { - _code << _indentation << _nameGen->generateDependent(i); - } - _code << " = "; - printParameter(Base(0.0)); - _code << ";\n"; - } - } - - size_t assignCount = 0; - for (size_t i = 0; i < variableOrder.size(); ++i) { - Node* it = variableOrder[i]; - - // check if a new function should start - if (assignCount >= _maxAssigmentsPerFunction && multiFunction && _currentLoops.empty()) { - assignCount = 0; - saveLocalFunction(localFuncNames, localFuncNames.empty() && info->zeroDependents); - } - - Node& node = *it; - - // a dependent variable assigned by a loop does require any source code (its done inside the loop) - if (node.getOperationType() == CGOpCode::DependentRefRhs) { - continue; // nothing to do (this operation is right hand side only) - } else if (node.getOperationType() == CGOpCode::TmpDcl) { // temporary variable declaration does not need any source code here - continue; // nothing to do (bogus operation) - } else if (node.getOperationType() == CGOpCode::LoopIndexedDep) { - // try to detect a pattern and use a loop instead of individual assignments - i = printLoopIndexDeps(variableOrder, i); - continue; - } - - assignCount += printAssigment(node); - } - - if (localFuncNames.size() > 0 && assignCount > 0) { - assignCount = 0; - saveLocalFunction(localFuncNames, false); - } - } - - if (localFuncNames.size() > 0) { - /** - * Create the wrapper function which calls the other functions - */ - CPPADCG_ASSERT_KNOWN(tmpArg[0].array, - "The temporary variables must be saved in an array in order to generate multiple functions"); - - _code << ATOMICFUN_STRUCT_DEFINITION << "\n\n"; - // forward declarations - for (size_t i = 0; i < localFuncNames.size(); i++) { - _code << "void " << localFuncNames[i] << "(" << localFuncArgDcl_ << ");\n"; - } - _code << "\n" - << "void " << _functionName << "(" << funcArgDcl_ << ") {\n"; - _nameGen->customFunctionVariableDeclarations(_code); - _code << generateIndependentVariableDeclaration() << "\n"; - _code << generateDependentVariableDeclaration() << "\n"; - _code << generateTemporaryVariableDeclaration(true, false, - info->atomicFunctionsMaxForward, - info->atomicFunctionsMaxReverse) << "\n"; - _nameGen->prepareCustomFunctionVariables(_code); - for (size_t i = 0; i < localFuncNames.size(); i++) { - _code << _spaces << localFuncNames[i] << "(" << localFuncArgs_ << ");\n"; - } - } - - // dependent duplicates - if (dependentDuplicates.size() > 0) { - _code << _spaces << "// variable duplicates: " << dependentDuplicates.size() << "\n"; - for (size_t index : dependentDuplicates) { - const CG& dep = (*_dependent)[index]; - std::string varName = _nameGen->generateDependent(index); - const std::string& origVarName = *dep.getOperationNode()->getName(); - - _code << _spaces << varName << " " << _depAssignOperation << " " << origVarName << ";\n"; - } - } - - // constant dependent variables - bool commentWritten = false; - for (size_t i = 0; i < dependent.size(); i++) { - if (dependent[i].isParameter()) { - if (!_ignoreZeroDepAssign || !dependent[i].isIdenticalZero()) { - if (!commentWritten) { - _code << _spaces << "// dependent variables without operations\n"; - commentWritten = true; - } - std::string varName = _nameGen->generateDependent(i); - _code << _spaces << varName << " " << _depAssignOperation << " "; - printParameter(dependent[i].getValue()); - _code << ";\n"; - } - } else if (dependent[i].getOperationNode()->getOperationType() == CGOpCode::Inv) { - if (!commentWritten) { - _code << _spaces << "// dependent variables without operations\n"; - commentWritten = true; - } - std::string varName = _nameGen->generateDependent(i); - const std::string& indepName = *dependent[i].getOperationNode()->getName(); - _code << _spaces << varName << " " << _depAssignOperation << " " << indepName << ";\n"; - } - } - - /** - * encapsulate the code in a function - */ - if (createFunction) { - if (localFuncNames.empty()) { - _ss << "#include \n" - "#include \n\n" - << ATOMICFUN_STRUCT_DEFINITION << "\n\n" - << "void " << _functionName << "(" << funcArgDcl_ << ") {\n"; - _nameGen->customFunctionVariableDeclarations(_ss); - _ss << generateIndependentVariableDeclaration() << "\n"; - _ss << generateDependentVariableDeclaration() << "\n"; - _ss << generateTemporaryVariableDeclaration(false, info->zeroDependents, - info->atomicFunctionsMaxForward, - info->atomicFunctionsMaxReverse) << "\n"; - _nameGen->prepareCustomFunctionVariables(_ss); - _ss << _code.str(); - _nameGen->finalizeCustomFunctionVariables(_ss); - _ss << "}\n\n"; - - out << _ss.str(); - - if (_sources != nullptr) { - (*_sources)[_functionName + ".c"] = _ss.str(); - } - } else { - _nameGen->finalizeCustomFunctionVariables(_code); - _code << "}\n\n"; - - (*_sources)[_functionName + ".c"] = _code.str(); - } - } else { - out << _code.str(); - } - } - - inline size_t getVariableID(const Node& node) const { - return _info->varId[node]; - } - - inline unsigned printAssigment(Node& node) { - return printAssigment(node, node); - } - - inline unsigned printAssigment(Node& nodeName, - const Arg& nodeRhs) { - if (nodeRhs.getOperation() != nullptr) { - return printAssigment(nodeName, *nodeRhs.getOperation()); - } else { - printAssigmentStart(nodeName); - printParameter(*nodeRhs.getParameter()); - printAssigmentEnd(nodeName); - return 1; - } - } - - inline unsigned printAssigment(Node& nodeName, - Node& nodeRhs) { - bool createsVar = directlyAssignsVariable(nodeRhs); // do we need to do the assignment here? - if (!createsVar) { - printAssigmentStart(nodeName); - } - unsigned lines = printExpressionNoVarCheck(nodeRhs); - if (!createsVar) { - printAssigmentEnd(nodeRhs); - } - - if (nodeRhs.getOperationType() == CGOpCode::ArrayElement) { - Node* array = nodeRhs.getArguments()[0].getOperation(); - size_t arrayId = getVariableID(*array); - size_t pos = nodeRhs.getInfo()[0]; - if (array->getOperationType() == CGOpCode::ArrayCreation) - _tmpArrayValues[arrayId - 1 + pos] = nullptr; // this could probably be removed! - else - _tmpSparseArrayValues[arrayId - 1 + pos] = nullptr; // this could probably be removed! - } - - return lines; - } - - inline virtual void printAssigmentStart(Node& op) { - printAssigmentStart(op, createVariableName(op), isDependent(op)); - } - - inline virtual void printAssigmentStart(Node& node, const std::string& varName, bool isDep) { - if (!isDep) { - _temporary[getVariableID(node)] = &node; - } - - _code << _indentation << varName << " "; - if (isDep) { - CGOpCode op = node.getOperationType(); - if (op == CGOpCode::DependentMultiAssign || (op == CGOpCode::LoopIndexedDep && node.getInfo()[1] == 1)) { - _code << "+="; - } else { - _code << _depAssignOperation; - } - } else { - _code << "="; - } - _code << " "; - } - - inline virtual void printAssigmentEnd(Node& op) { - _code << ";\n"; - } - - virtual std::string argumentDeclaration(const FuncArgument& funcArg) const { - std::string dcl = _baseTypeName; - if (funcArg.array) { - dcl += "*"; - } - return dcl + " " + funcArg.name; - } - - virtual void saveLocalFunction(std::vector& localFuncNames, - bool zeroDependentArray) { - _ss << _functionName << "__" << (localFuncNames.size() + 1); - std::string funcName = _ss.str(); - _ss.str(""); - - _ss << "#include \n" - "#include \n\n" - << ATOMICFUN_STRUCT_DEFINITION << "\n\n" - << "void " << funcName << "(" << localFuncArgDcl_ << ") {\n"; - _nameGen->customFunctionVariableDeclarations(_ss); - _ss << generateIndependentVariableDeclaration() << "\n"; - _ss << generateDependentVariableDeclaration() << "\n"; - size_t arraySize = _nameGen->getMaxTemporaryArrayVariableID(); - size_t sArraySize = _nameGen->getMaxTemporarySparseArrayVariableID(); - if (arraySize > 0 || sArraySize > 0) { - _ss << _spaces << _baseTypeName << "* " << auxArrayName_ << ";\n"; - } - - generateArrayContainersDeclaration(_ss, - _info->atomicFunctionsMaxForward, - _info->atomicFunctionsMaxReverse); - - if (arraySize > 0 || sArraySize > 0 || zeroDependentArray) { - _ss << _spaces << U_INDEX_TYPE << " i;\n"; - } - - // loop indexes - createIndexDeclaration(); - - _nameGen->prepareCustomFunctionVariables(_ss); - _ss << _code.str(); - _nameGen->finalizeCustomFunctionVariables(_ss); - _ss << "}\n\n"; - - (*_sources)[funcName + ".c"] = _ss.str(); - localFuncNames.push_back(funcName); - - _code.str(""); - _ss.str(""); - } - - virtual bool createsNewVariable(const Node& var, - size_t totalUseCount) const override { - CGOpCode op = var.getOperationType(); - if (totalUseCount > 1) { - return op != CGOpCode::ArrayElement && op != CGOpCode::Index && op != CGOpCode::IndexDeclaration && op != CGOpCode::Tmp; - } else { - return ( op == CGOpCode::ArrayCreation || - op == CGOpCode::SparseArrayCreation || - op == CGOpCode::AtomicForward || - op == CGOpCode::AtomicReverse || - op == CGOpCode::ComLt || - op == CGOpCode::ComLe || - op == CGOpCode::ComEq || - op == CGOpCode::ComGe || - op == CGOpCode::ComGt || - op == CGOpCode::ComNe || - op == CGOpCode::LoopIndexedDep || - op == CGOpCode::LoopIndexedTmp || - op == CGOpCode::IndexAssign || - op == CGOpCode::Assign) && - op != CGOpCode::CondResult; - } - } - - virtual bool requiresVariableName(const Node& var) const { - CGOpCode op = var.getOperationType(); - if (_info->totalUseCount.get(var) > 1) { - return (op != CGOpCode::Pri && - op != CGOpCode::AtomicForward && - op != CGOpCode::AtomicReverse && - op != CGOpCode::LoopStart && - op != CGOpCode::LoopEnd && - op != CGOpCode::Index && - op != CGOpCode::IndexAssign && - op != CGOpCode::StartIf && - op != CGOpCode::ElseIf && - op != CGOpCode::Else && - op != CGOpCode::EndIf && - op != CGOpCode::CondResult && - op != CGOpCode::LoopIndexedTmp && - op != CGOpCode::Tmp); - } else { - return isCondAssign(op); - } - } - - /** - * Whether or not this operation assign its expression to a variable by - * itself. - * - * @param var the operation node - * @return - */ - virtual bool directlyAssignsVariable(const Node& var) const { - CGOpCode op = var.getOperationType(); - return isCondAssign(op) || - op == CGOpCode::Pri || - op == CGOpCode::ArrayCreation || - op == CGOpCode::SparseArrayCreation || - op == CGOpCode::AtomicForward || - op == CGOpCode::AtomicReverse || - op == CGOpCode::DependentMultiAssign || - op == CGOpCode::LoopStart || - op == CGOpCode::LoopEnd || - op == CGOpCode::IndexAssign || - op == CGOpCode::StartIf || - op == CGOpCode::ElseIf || - op == CGOpCode::Else || - op == CGOpCode::EndIf || - op == CGOpCode::CondResult || - op == CGOpCode::IndexDeclaration; - } - - virtual bool requiresVariableArgument(enum CGOpCode op, size_t argIndex) const override { - return op == CGOpCode::Sign || op == CGOpCode::CondResult || op == CGOpCode::Pri; - } - - inline const std::string& createVariableName(Node& var) { - CGOpCode op = var.getOperationType(); - CPPADCG_ASSERT_UNKNOWN(getVariableID(var) > 0); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::AtomicForward); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::AtomicReverse); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::LoopStart); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::LoopEnd); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::Index); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::IndexAssign); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::IndexDeclaration); - - if (var.getName() == nullptr) { - if (op == CGOpCode::ArrayCreation) { - var.setName(_nameGen->generateTemporaryArray(var, getVariableID(var))); - - } else if (op == CGOpCode::SparseArrayCreation) { - var.setName(_nameGen->generateTemporarySparseArray(var, getVariableID(var))); - - } else if (op == CGOpCode::LoopIndexedDep) { - size_t pos = var.getInfo()[0]; - const IndexPattern* ip = _info->loopDependentIndexPatterns[pos]; - var.setName(_nameGen->generateIndexedDependent(var, getVariableID(var), *ip)); - - } else if (op == CGOpCode::LoopIndexedIndep) { - size_t pos = var.getInfo()[1]; - const IndexPattern* ip = _info->loopIndependentIndexPatterns[pos]; - var.setName(_nameGen->generateIndexedIndependent(var, getVariableID(var), *ip)); - - } else if (getVariableID(var) <= _independentSize) { - // independent variable - var.setName(_nameGen->generateIndependent(var, getVariableID(var))); - - } else if (getVariableID(var) < _minTemporaryVarID) { - // dependent variable - std::map::const_iterator it = _dependentIDs.find(getVariableID(var)); - CPPADCG_ASSERT_UNKNOWN(it != _dependentIDs.end()); - - size_t index = it->second; - var.setName(_nameGen->generateDependent(index)); - } else if (op == CGOpCode::Pri) { - CPPADCG_ASSERT_KNOWN(var.getArguments().size() == 1, "Invalid number of arguments for print operation"); - Node* tmpVar = var.getArguments()[0].getOperation(); - CPPADCG_ASSERT_KNOWN(tmpVar != nullptr, "Invalid argument for print operation"); - return createVariableName(*tmpVar); - - } else if (op == CGOpCode::LoopIndexedTmp || op == CGOpCode::Tmp) { - CPPADCG_ASSERT_KNOWN(var.getArguments().size() >= 1, "Invalid number of arguments for loop indexed temporary operation"); - Node* tmpVar = var.getArguments()[0].getOperation(); - CPPADCG_ASSERT_KNOWN(tmpVar != nullptr && tmpVar->getOperationType() == CGOpCode::TmpDcl, "Invalid arguments for loop indexed temporary operation"); - return createVariableName(*tmpVar); - - } else { - // temporary variable - var.setName(_nameGen->generateTemporary(var, getVariableID(var))); - } - } - - - return *var.getName(); - } - - virtual bool requiresVariableDependencies() const override { - return false; - } - - virtual void printIndependentVariableName(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 0, "Invalid number of arguments for independent variable"); - - _code << _nameGen->generateIndependent(op, getVariableID(op)); - } - - virtual unsigned print(const Arg& arg) { - if (arg.getOperation() != nullptr) { - // expression - return printExpression(*arg.getOperation()); - } else { - // parameter - printParameter(*arg.getParameter()); - return 1; - } - } - - virtual unsigned printExpression(Node& op) { - if (getVariableID(op) > 0) { - // use variable name - _code << createVariableName(op); - return 1; - } else { - // print expression code - return printExpressionNoVarCheck(op); - } - } - - virtual unsigned printExpressionNoVarCheck(Node& node) { - CGOpCode op = node.getOperationType(); - switch (op) { - case CGOpCode::ArrayCreation: - printArrayCreationOp(node); - break; - case CGOpCode::SparseArrayCreation: - printSparseArrayCreationOp(node); - break; - case CGOpCode::ArrayElement: - printArrayElementOp(node); - break; - case CGOpCode::Assign: - return printAssignOp(node); - - case CGOpCode::Abs: - case CGOpCode::Acos: - case CGOpCode::Asin: - case CGOpCode::Atan: - case CGOpCode::Cosh: - case CGOpCode::Cos: - case CGOpCode::Exp: - case CGOpCode::Log: - case CGOpCode::Sinh: - case CGOpCode::Sin: - case CGOpCode::Sqrt: - case CGOpCode::Tanh: - case CGOpCode::Tan: -#if CPPAD_USE_CPLUSPLUS_2011 - case CGOpCode::Erf: - case CGOpCode::Asinh: - case CGOpCode::Acosh: - case CGOpCode::Atanh: - case CGOpCode::Expm1: - case CGOpCode::Log1p: -#endif - printUnaryFunction(node); - break; - case CGOpCode::AtomicForward: // atomicFunction.forward(q, p, vx, vy, tx, ty) - printAtomicForwardOp(node); - break; - case CGOpCode::AtomicReverse: // atomicFunction.reverse(p, tx, ty, px, py) - printAtomicReverseOp(node); - break; - case CGOpCode::Add: - printOperationAdd(node); - break; - case CGOpCode::Alias: - return printOperationAlias(node); - - case CGOpCode::ComLt: - case CGOpCode::ComLe: - case CGOpCode::ComEq: - case CGOpCode::ComGe: - case CGOpCode::ComGt: - case CGOpCode::ComNe: - printConditionalAssignment(node); - break; - case CGOpCode::Div: - printOperationDiv(node); - break; - case CGOpCode::Inv: - printIndependentVariableName(node); - break; - case CGOpCode::Mul: - printOperationMul(node); - break; - case CGOpCode::Pow: - printPowFunction(node); - break; - case CGOpCode::Pri: - printPrintOperation(node); - break; - case CGOpCode::Sign: - printSignFunction(node); - break; - case CGOpCode::Sub: - printOperationMinus(node); - break; - - case CGOpCode::UnMinus: - printOperationUnaryMinus(node); - break; - - case CGOpCode::DependentMultiAssign: - return printDependentMultiAssign(node); - - case CGOpCode::Index: - return 0; // nothing to do - case CGOpCode::IndexAssign: - printIndexAssign(node); - break; - case CGOpCode::IndexDeclaration: - return 0; // already done - - case CGOpCode::LoopStart: - printLoopStart(node); - break; - case CGOpCode::LoopIndexedIndep: - printLoopIndexedIndep(node); - break; - case CGOpCode::LoopIndexedDep: - printLoopIndexedDep(node); - break; - case CGOpCode::LoopIndexedTmp: - printLoopIndexedTmp(node); - break; - case CGOpCode::TmpDcl: - // nothing to do - return 0; - case CGOpCode::Tmp: - printTmpVar(node); - break; - case CGOpCode::LoopEnd: - printLoopEnd(node); - break; - case CGOpCode::IndexCondExpr: - printIndexCondExprOp(node); - break; - case CGOpCode::StartIf: - printStartIf(node); - break; - case CGOpCode::ElseIf: - printElseIf(node); - break; - case CGOpCode::Else: - printElse(node); - break; - case CGOpCode::EndIf: - printEndIf(node); - break; - case CGOpCode::CondResult: - printCondResult(node); - break; - case CGOpCode::UserCustom: - printUserCustom(node); - break; - default: - throw CGException("Unknown operation code '", op, "'."); - } - return 1; - } - - virtual unsigned printAssignOp(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 1, "Invalid number of arguments for assign operation"); - - return print(node.getArguments()[0]); - } - - virtual void printUnaryFunction(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 1, "Invalid number of arguments for unary function"); - - switch (op.getOperationType()) { - case CGOpCode::Abs: - _code << absFuncName(); - break; - case CGOpCode::Acos: - _code << acosFuncName(); - break; - case CGOpCode::Asin: - _code << asinFuncName(); - break; - case CGOpCode::Atan: - _code << atanFuncName(); - break; - case CGOpCode::Cosh: - _code << coshFuncName(); - break; - case CGOpCode::Cos: - _code << cosFuncName(); - break; - case CGOpCode::Exp: - _code << expFuncName(); - break; - case CGOpCode::Log: - _code << logFuncName(); - break; - case CGOpCode::Sinh: - _code << sinhFuncName(); - break; - case CGOpCode::Sin: - _code << sinFuncName(); - break; - case CGOpCode::Sqrt: - _code << sqrtFuncName(); - break; - case CGOpCode::Tanh: - _code << tanhFuncName(); - break; - case CGOpCode::Tan: - _code << tanFuncName(); - break; -#if CPPAD_USE_CPLUSPLUS_2011 - case CGOpCode::Erf: - _code << erfFuncName(); - break; - case CGOpCode::Asinh: - _code << asinhFuncName(); - break; - case CGOpCode::Acosh: - _code << acoshFuncName(); - break; - case CGOpCode::Atanh: - _code << atanhFuncName(); - break; - case CGOpCode::Expm1: - _code << expm1FuncName(); - break; - case CGOpCode::Log1p: - _code << log1pFuncName(); - break; -#endif - default: - throw CGException("Unknown function name for operation code '", op.getOperationType(), "'."); - } - - _code << "("; - print(op.getArguments()[0]); - _code << ")"; - } - - virtual void printPowFunction(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for pow() function"); - - _code << powFuncName() << "("; - print(op.getArguments()[0]); - _code << ", "; - print(op.getArguments()[1]); - _code << ")"; - } - - virtual void printSignFunction(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 1, "Invalid number of arguments for sign() function"); - CPPADCG_ASSERT_UNKNOWN(op.getArguments()[0].getOperation() != nullptr); - CPPADCG_ASSERT_UNKNOWN(getVariableID(*op.getArguments()[0].getOperation()) > 0); - - Node& arg = *op.getArguments()[0].getOperation(); - - const std::string& argName = createVariableName(arg); - - _code << "(" << argName << " " << _C_COMP_OP_GT << " "; - printParameter(Base(0.0)); - _code << "?"; - printParameter(Base(1.0)); - _code << ":(" << argName << " " << _C_COMP_OP_LT << " "; - printParameter(Base(0.0)); - _code << "?"; - printParameter(Base(-1.0)); - _code << ":"; - printParameter(Base(0.0)); - _code << "))"; - } - - virtual unsigned printOperationAlias(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 1, "Invalid number of arguments for alias"); - return print(op.getArguments()[0]); - } - - virtual void printOperationAdd(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for addition"); - - const Arg& left = op.getArguments()[0]; - const Arg& right = op.getArguments()[1]; - - if(right.getParameter() == nullptr || (*right.getParameter() >= 0)) { - print(left); - _code << " + "; - print(right); - } else { - // right has a negative parameter so we would get v0 + -v1 - print(left); - _code << " - "; - printParameter(-*right.getParameter()); // make it positive - } - } - - virtual void printOperationMinus(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for subtraction"); - - const Arg& left = op.getArguments()[0]; - const Arg& right = op.getArguments()[1]; - - if(right.getParameter() == nullptr || (*right.getParameter() >= 0)) { - bool encloseRight = encloseInParenthesesMul(right.getOperation()); - - print(left); - _code << " - "; - if (encloseRight) { - _code << "("; - } - print(right); - if (encloseRight) { - _code << ")"; - } - } else { - // right has a negative parameter so we would get v0 - -v1 - print(left); - _code << " + "; - printParameter(-*right.getParameter()); // make it positive - } - } - - inline bool encloseInParenthesesDiv(const Node* node) const { - while (node != nullptr) { - if (getVariableID(*node) != 0) - return false; - if (node->getOperationType() == CGOpCode::Alias) - node = node->getArguments()[0].getOperation(); - else - break; - } - return node != nullptr && - getVariableID(*node) == 0 && - !isFunction(node->getOperationType()); - } - - virtual void printOperationDiv(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for division"); - - const Arg& left = op.getArguments()[0]; - const Arg& right = op.getArguments()[1]; - - bool encloseLeft = encloseInParenthesesDiv(left.getOperation()); - bool encloseRight = encloseInParenthesesDiv(right.getOperation()); - - if (encloseLeft) { - _code << "("; - } - print(left); - if (encloseLeft) { - _code << ")"; - } - _code << " / "; - if (encloseRight) { - _code << "("; - } - print(right); - if (encloseRight) { - _code << ")"; - } - } - - inline bool encloseInParenthesesMul(const Node* node) const { - while (node != nullptr) { - if (getVariableID(*node) != 0) - return false; - else if (node->getOperationType() == CGOpCode::Alias) - node = node->getArguments()[0].getOperation(); - else - break; - } - return node != nullptr && - getVariableID(*node) == 0 && - node->getOperationType() != CGOpCode::Div && - node->getOperationType() != CGOpCode::Mul && - !isFunction(node->getOperationType()); - } - - virtual void printOperationMul(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for multiplication"); - - const Arg& left = op.getArguments()[0]; - const Arg& right = op.getArguments()[1]; - - bool encloseLeft = encloseInParenthesesMul(left.getOperation()); - bool encloseRight = encloseInParenthesesMul(right.getOperation()); - - if (encloseLeft) { - _code << "("; - } - print(left); - if (encloseLeft) { - _code << ")"; - } - _code << " * "; - if (encloseRight) { - _code << "("; - } - print(right); - if (encloseRight) { - _code << ")"; - } - } - - virtual void printOperationUnaryMinus(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 1, "Invalid number of arguments for unary minus"); - - const Arg& arg = op.getArguments()[0]; - - bool enclose = encloseInParenthesesMul(arg.getOperation()); - - _code << "-"; - if (enclose) { - _code << "("; - } else { - _code << " "; // there may be several - together -> space required - } - print(arg); - if (enclose) { - _code << ")"; - } - } - - virtual void printPrintOperation(const Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::Pri, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 1, "Invalid number of arguments for print operation"); - - const PrintOperationNode& pnode = static_cast&> (node); - std::string before = pnode.getBeforeString(); - replaceString(before, "\n", "\\n"); - replaceString(before, "\"", "\\\""); - std::string after = pnode.getAfterString(); - replaceString(after, "\n", "\\n"); - replaceString(after, "\"", "\\\""); - - _code << _indentation << "fprintf(stderr, \"" << before << getPrintfBaseFormat() << after << "\""; - const std::vector& args = pnode.getArguments(); - for (size_t a = 0; a < args.size(); a++) { - _code << ", "; - print(args[a]); - } - _code << ");\n"; - } - - virtual void printConditionalAssignment(Node& node) { - CPPADCG_ASSERT_UNKNOWN(getVariableID(node) > 0); - - const std::vector& args = node.getArguments(); - const Arg &left = args[0]; - const Arg &right = args[1]; - const Arg &trueCase = args[2]; - const Arg &falseCase = args[3]; - - bool isDep = isDependent(node); - const std::string& varName = createVariableName(node); - - if ((trueCase.getParameter() != nullptr && falseCase.getParameter() != nullptr && *trueCase.getParameter() == *falseCase.getParameter()) || - (trueCase.getOperation() != nullptr && falseCase.getOperation() != nullptr && trueCase.getOperation() == falseCase.getOperation())) { - // true and false cases are the same - printAssigmentStart(node, varName, isDep); - print(trueCase); - printAssigmentEnd(node); - } else { - _code << _indentation << "if( "; - print(left); - _code << " " << getComparison(node.getOperationType()) << " "; - print(right); - _code << " ) {\n"; - _code << _spaces; - printAssigmentStart(node, varName, isDep); - print(trueCase); - printAssigmentEnd(node); - _code << _indentation << "} else {\n"; - _code << _spaces; - printAssigmentStart(node, varName, isDep); - print(falseCase); - printAssigmentEnd(node); - _code << _indentation << "}\n"; - } - } - - inline bool isSameArgument(const Arg& newArg, - const Arg* oldArg) { - if (oldArg != nullptr) { - if (oldArg->getParameter() != nullptr) { - if (newArg.getParameter() != nullptr) { - return (*newArg.getParameter() == *oldArg->getParameter()); - } - } else { - return (newArg.getOperation() == oldArg->getOperation()); - } - } - return false; - } - - virtual void printArrayCreationOp(Node& op); - - virtual void printSparseArrayCreationOp(Node& op); - - inline void printArrayStructInit(const std::string& dataArrayName, - size_t pos, - const std::vector& arrays, - size_t k); - - inline void printArrayStructInit(const std::string& dataArrayName, - Node& array); - - inline void markArrayChanged(Node& ty); - - inline size_t printArrayCreationUsingLoop(size_t startPos, - Node& array, - size_t startj, - std::vector& tmpArrayValues); - - inline std::string getTempArrayName(const Node& op); - - virtual void printArrayElementOp(Node& op); - - virtual void printAtomicForwardOp(Node& atomicFor) { - CPPADCG_ASSERT_KNOWN(atomicFor.getInfo().size() == 3, "Invalid number of information elements for atomic forward operation"); - int q = atomicFor.getInfo()[1]; - int p = atomicFor.getInfo()[2]; - size_t p1 = p + 1; - const std::vector& opArgs = atomicFor.getArguments(); - CPPADCG_ASSERT_KNOWN(opArgs.size() == p1 * 2, "Invalid number of arguments for atomic forward operation"); - - size_t id = atomicFor.getInfo()[0]; - size_t atomicIndex = _info->atomicFunctionId2Index.at(id); - - std::vector tx(p1), ty(p1); - for (size_t k = 0; k < p1; k++) { - tx[k] = opArgs[0 * p1 + k].getOperation(); - ty[k] = opArgs[1 * p1 + k].getOperation(); - } - - CPPADCG_ASSERT_KNOWN(tx[0]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - CPPADCG_ASSERT_KNOWN(p == 0 || tx[1]->getOperationType() == CGOpCode::SparseArrayCreation, "Invalid array type"); - - CPPADCG_ASSERT_KNOWN(ty[p]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - - // tx - for (size_t k = 0; k < p1; k++) { - printArrayStructInit(_ATOMIC_TX, k, tx, k); // also does indentation - } - // ty - printArrayStructInit(_ATOMIC_TY, *ty[p]); // also does indentation - _ss.str(""); - - _code << _indentation << "atomicFun.forward(atomicFun.libModel, " - << atomicIndex << ", " << q << ", " << p << ", " - << _ATOMIC_TX << ", &" << _ATOMIC_TY << "); // " - << _info->atomicFunctionId2Name.at(id) - << "\n"; - - /** - * the values of ty are now changed - */ - markArrayChanged(*ty[p]); - } - - virtual void printAtomicReverseOp(Node& atomicRev) { - CPPADCG_ASSERT_KNOWN(atomicRev.getInfo().size() == 2, "Invalid number of information elements for atomic reverse operation"); - int p = atomicRev.getInfo()[1]; - size_t p1 = p + 1; - const std::vector& opArgs = atomicRev.getArguments(); - CPPADCG_ASSERT_KNOWN(opArgs.size() == p1 * 4, "Invalid number of arguments for atomic reverse operation"); - - size_t id = atomicRev.getInfo()[0]; - size_t atomicIndex = _info->atomicFunctionId2Index.at(id); - std::vector tx(p1), px(p1), py(p1); - for (size_t k = 0; k < p1; k++) { - tx[k] = opArgs[0 * p1 + k].getOperation(); - px[k] = opArgs[2 * p1 + k].getOperation(); - py[k] = opArgs[3 * p1 + k].getOperation(); - } - - CPPADCG_ASSERT_KNOWN(tx[0]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - CPPADCG_ASSERT_KNOWN(p == 0 || tx[1]->getOperationType() == CGOpCode::SparseArrayCreation, "Invalid array type"); - - CPPADCG_ASSERT_KNOWN(px[0]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - - CPPADCG_ASSERT_KNOWN(py[0]->getOperationType() == CGOpCode::SparseArrayCreation, "Invalid array type"); - CPPADCG_ASSERT_KNOWN(p == 0 || py[1]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - - // tx - for (size_t k = 0; k < p1; k++) { - printArrayStructInit(_ATOMIC_TX, k, tx, k); // also does indentation - } - // py - for (size_t k = 0; k < p1; k++) { - printArrayStructInit(_ATOMIC_PY, k, py, k); // also does indentation - } - // px - printArrayStructInit(_ATOMIC_PX, *px[0]); // also does indentation - _ss.str(""); - - _code << _indentation << "atomicFun.reverse(atomicFun.libModel, " - << atomicIndex << ", " << p << ", " - << _ATOMIC_TX << ", &" << _ATOMIC_PX << ", " << _ATOMIC_PY << "); // " - << _info->atomicFunctionId2Name.at(id) - << "\n"; - - /** - * the values of px are now changed - */ - markArrayChanged(*px[0]); - } - - virtual unsigned printDependentMultiAssign(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::DependentMultiAssign, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() > 0, "Invalid number of arguments"); - - const std::vector& args = node.getArguments(); - for (size_t a = 0; a < args.size(); a++) { - bool useArg = false; - const Arg& arg = args[a]; - if (arg.getParameter() != nullptr) { - useArg = true; - } else { - CGOpCode op = arg.getOperation()->getOperationType(); - useArg = op != CGOpCode::DependentRefRhs && op != CGOpCode::LoopEnd && op != CGOpCode::EndIf; - } - - if (useArg) { - printAssigment(node, arg); // ignore other arguments! - return 1; - } - } - return 0; - } - - virtual void printLoopStart(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopStart, "Invalid node type"); - - LoopStartOperationNode& lnode = static_cast&> (node); - _currentLoops.push_back(&lnode); - - const std::string& jj = *lnode.getIndex().getName(); - std::string iterationCount; - if (lnode.getIterationCountNode() != nullptr) { - iterationCount = *lnode.getIterationCountNode()->getIndex().getName(); - } else { - std::ostringstream oss; - oss << lnode.getIterationCount(); - iterationCount = oss.str(); - } - - _code << _spaces << "for(" - << jj << " = 0; " - << jj << " < " << iterationCount << "; " - << jj << "++) {\n"; - _indentation += _spaces; - } - - virtual void printLoopEnd(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopEnd, "Invalid node type"); - - _indentation.resize(_indentation.size() - _spaces.size()); - - _code << _indentation << "}\n"; - - _currentLoops.pop_back(); - } - - - virtual size_t printLoopIndexDeps(const std::vector& variableOrder, - size_t pos); - - virtual size_t printLoopIndexedDepsUsingLoop(const std::vector& variableOrder, - size_t starti); - - virtual void printLoopIndexedDep(Node& node); - - virtual void printLoopIndexedIndep(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopIndexedIndep, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getInfo().size() == 1, "Invalid number of information elements for loop indexed independent operation"); - - // CGLoopIndexedIndepOp - size_t pos = node.getInfo()[1]; - const IndexPattern* ip = _info->loopIndependentIndexPatterns[pos]; - _code << _nameGen->generateIndexedIndependent(node, getVariableID(node), *ip); - } - - virtual void printLoopIndexedTmp(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopIndexedTmp, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 2, "Invalid number of arguments for loop indexed temporary operation"); - Node* tmpVar = node.getArguments()[0].getOperation(); - CPPADCG_ASSERT_KNOWN(tmpVar != nullptr && tmpVar->getOperationType() == CGOpCode::TmpDcl, "Invalid arguments for loop indexed temporary operation"); - - print(node.getArguments()[1]); - } - - virtual void printTmpVar(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::Tmp, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() > 0, "Invalid number of arguments for temporary variable usage operation"); - Node* tmpVar = node.getArguments()[0].getOperation(); - CPPADCG_ASSERT_KNOWN(tmpVar != nullptr && tmpVar->getOperationType() == CGOpCode::TmpDcl, "Invalid arguments for loop indexed temporary operation"); - - _code << *tmpVar->getName(); - } - - virtual void printIndexAssign(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::IndexAssign, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() > 0, "Invalid number of arguments for an index assignment operation"); - - IndexAssignOperationNode& inode = static_cast&> (node); - - const IndexPattern& ip = inode.getIndexPattern(); - _code << _indentation << (*inode.getIndex().getName()) - << " = " << indexPattern2String(ip, inode.getIndexPatternIndexes()) << ";\n"; - } - - virtual void printIndexCondExprOp(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::IndexCondExpr, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 1, "Invalid number of arguments for an index condition expression operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an index condition expression operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation()->getOperationType() == CGOpCode::Index, "Invalid argument for an index condition expression operation"); - - const std::vector& info = node.getInfo(); - - IndexOperationNode& iterationIndexOp = static_cast&> (*node.getArguments()[0].getOperation()); - const std::string& index = *iterationIndexOp.getIndex().getName(); - - printIndexCondExpr(_code, info, index); - } - - virtual void printStartIf(Node& node) { - /** - * the first argument is the condition, following arguments are - * just extra dependencies that must be defined outside the if - */ - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::StartIf, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 1, "Invalid number of arguments for an 'if start' operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an 'if start' operation"); - - _code << _indentation << "if("; - printIndexCondExprOp(*node.getArguments()[0].getOperation()); - _code << ") {\n"; - - _indentation += _spaces; - } - - virtual void printElseIf(Node& node) { - /** - * the first argument is the condition, the second argument is the - * if start node, the following arguments are assignments in the - * previous if branch - */ - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::ElseIf, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 2, "Invalid number of arguments for an 'else if' operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an 'else if' operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[1].getOperation() != nullptr, "Invalid argument for an 'else if' operation"); - - _indentation.resize(_indentation.size() - _spaces.size()); - - _code << _indentation << "} else if("; - printIndexCondExprOp(*node.getArguments()[1].getOperation()); - _code << ") {\n"; - - _indentation += _spaces; - } - - virtual void printElse(Node& node) { - /** - * the first argument is the if start node, the following arguments - * are assignments in the previous if branch - */ - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::Else, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 1, "Invalid number of arguments for an 'else' operation"); - - _indentation.resize(_indentation.size() - _spaces.size()); - - _code << _indentation << "} else {\n"; - - _indentation += _spaces; - } - - virtual void printEndIf(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::EndIf, "Invalid node type for an 'end if' operation"); - - _indentation.resize(_indentation.size() - _spaces.size()); - - _code << _indentation << "}\n"; - } - - virtual void printCondResult(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::CondResult, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 2, "Invalid number of arguments for an assignment inside an if/else operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an an assignment inside an if/else operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[1].getOperation() != nullptr, "Invalid argument for an an assignment inside an if/else operation"); - - // just follow the argument - Node& nodeArg = *node.getArguments()[1].getOperation(); - printAssigment(nodeArg); - } - - virtual void printUserCustom(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::UserCustom, "Invalid node type"); - - throw CGException("Unable to generate C source code for user custom operation nodes."); - } - - inline bool isDependent(const Node& arg) const { - if (arg.getOperationType() == CGOpCode::LoopIndexedDep) { - return true; - } - size_t id = getVariableID(arg); - return id > _independentSize && id < _minTemporaryVarID; - } - - virtual void printParameter(const Base& value) { - // make sure all digits of floating point values are printed - std::ostringstream os; - os << std::setprecision(_parameterPrecision) << value; - - std::string number = os.str(); - _code << number; - - if (std::abs(value) > Base(0) && value != Base(1) && value != Base(-1)) { - if (number.find('.') == std::string::npos && number.find('e') == std::string::npos) { - // also make sure there is always a '.' after the number in - // order to avoid integer overflows - _code << '.'; - } - } - } - - virtual const std::string& getComparison(enum CGOpCode op) const { - switch (op) { - case CGOpCode::ComLt: - return _C_COMP_OP_LT; - - case CGOpCode::ComLe: - return _C_COMP_OP_LE; - - case CGOpCode::ComEq: - return _C_COMP_OP_EQ; - - case CGOpCode::ComGe: - return _C_COMP_OP_GE; - - case CGOpCode::ComGt: - return _C_COMP_OP_GT; - - case CGOpCode::ComNe: - return _C_COMP_OP_NE; - - default: - CPPAD_ASSERT_UNKNOWN(0); - } - throw CGException("Invalid comparison operator code"); // should never get here - } - - inline const std::string& getPrintfBaseFormat() { - static const std::string format; // empty string - return format; - } - - static bool isFunction(enum CGOpCode op) { - return isUnaryFunction(op) || op == CGOpCode::Pow; - } - - static bool isUnaryFunction(enum CGOpCode op) { - switch (op) { - case CGOpCode::Abs: - case CGOpCode::Acos: - case CGOpCode::Asin: - case CGOpCode::Atan: - case CGOpCode::Cosh: - case CGOpCode::Cos: - case CGOpCode::Exp: - case CGOpCode::Log: - case CGOpCode::Sinh: - case CGOpCode::Sin: - case CGOpCode::Sqrt: - case CGOpCode::Tanh: - case CGOpCode::Tan: -#if CPPAD_USE_CPLUSPLUS_2011 - case CGOpCode::Erf: - case CGOpCode::Asinh: - case CGOpCode::Acosh: - case CGOpCode::Atanh: - case CGOpCode::Expm1: - case CGOpCode::Log1p: -#endif - return true; - default: - return false; - } - } - - inline static bool isCondAssign(enum CGOpCode op) { - switch (op) { - case CGOpCode::ComLt: - case CGOpCode::ComLe: - case CGOpCode::ComEq: - case CGOpCode::ComGe: - case CGOpCode::ComGt: - case CGOpCode::ComNe: - return true; - default: - return false; - } - } -private: - - class AtomicFuncArray { - public: - std::string data; - unsigned long size; - bool sparse; - size_t idx_id; - unsigned long nnz; - unsigned short scope; - }; -}; -template -const std::string LanguageC::U_INDEX_TYPE = "unsigned long"; - -template -const std::string LanguageC::_C_COMP_OP_LT = "<"; -template -const std::string LanguageC::_C_COMP_OP_LE = "<="; -template -const std::string LanguageC::_C_COMP_OP_EQ = "=="; -template -const std::string LanguageC::_C_COMP_OP_GE = ">="; -template -const std::string LanguageC::_C_COMP_OP_GT = ">"; -template -const std::string LanguageC::_C_COMP_OP_NE = "!="; - -template -const std::string LanguageC::_C_STATIC_INDEX_ARRAY = "index"; - -template -const std::string LanguageC::_C_SPARSE_INDEX_ARRAY = "idx"; - -template -const std::string LanguageC::_ATOMIC_TX = "atx"; - -template -const std::string LanguageC::_ATOMIC_TY = "aty"; - -template -const std::string LanguageC::_ATOMIC_PX = "apx"; - -template -const std::string LanguageC::_ATOMIC_PY = "apy"; - -template -const std::string LanguageC::ATOMICFUN_STRUCT_DEFINITION = "typedef struct Array {\n" -" void* data;\n" -" " + U_INDEX_TYPE + " size;\n" -" int sparse;\n" -" const " + U_INDEX_TYPE + "* idx;\n" -" " + U_INDEX_TYPE + " nnz;\n" -"} Array;\n" -"\n" -"struct LangCAtomicFun {\n" -" void* libModel;\n" -" int (*forward)(void* libModel, int atomicIndex, int q, int p, const Array tx[], Array* ty);\n" -" int (*reverse)(void* libModel, int atomicIndex, int p, const Array tx[], Array* px, const Array py[]);\n" -"};"; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/c/language_c_arrays.hpp b/ct_core/include/ct/external/cppad/cg/lang/c/language_c_arrays.hpp deleted file mode 100644 index 64d1c7077..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/c/language_c_arrays.hpp +++ /dev/null @@ -1,456 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_C_ARRAYS_INCLUDED -#define CPPAD_CG_LANGUAGE_C_ARRAYS_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -void LanguageC::printArrayCreationOp(OperationNode& array) { - CPPADCG_ASSERT_KNOWN(array.getArguments().size() > 0, "Invalid number of arguments for array creation operation"); - const size_t id = getVariableID(array); - const std::vector >& args = array.getArguments(); - const size_t argSize = args.size(); - - size_t startPos = id - 1; - - bool firstElement = true; - for (size_t i = 0; i < argSize; i++) { - bool newValue = !isSameArgument(args[i], _tmpArrayValues[startPos + i]); - - if (newValue) { - if (firstElement) { - _code << _indentation << auxArrayName_ << " = " << _nameGen->generateTemporaryArray(array, getVariableID(array)) << "; // size: " << args.size() << "\n"; - firstElement = false; - } - - // try to use a loop for element assignment - size_t newI = printArrayCreationUsingLoop(startPos, array, i, _tmpArrayValues); - - if (newI == i) { - // individual element assignment - _code << _indentation << auxArrayName_ << "[" << i << "] = "; - print(args[i]); - _code << ";\n"; - - _tmpArrayValues[startPos + i] = &args[i]; - - } else { - i = newI - 1; - } - } - } -} - -template -void LanguageC::printSparseArrayCreationOp(OperationNode& array) { - const std::vector& info = array.getInfo(); - CPPADCG_ASSERT_KNOWN(info.size() > 0, "Invalid number of information elements for sparse array creation operation"); - - const std::vector >& args = array.getArguments(); - const size_t argSize = args.size(); - - CPPADCG_ASSERT_KNOWN(info.size() == argSize + 1, "Invalid number of arguments for sparse array creation operation"); - - if (argSize == 0) - return; // empty array - - const size_t id = getVariableID(array); - size_t startPos = id - 1; - - bool firstElement = true; - for (size_t i = 0; i < argSize; i++) { - bool newValue = !isSameArgument(args[i], _tmpSparseArrayValues[startPos + i]); - - if (newValue) { - if (firstElement) { - _code << _indentation << auxArrayName_ << " = " << _nameGen->generateTemporarySparseArray(array, getVariableID(array)) - << "; // nnz: " << args.size() << " size:" << info[0] << "\n"; - firstElement = false; - } - - // try to use a loop for element assignment - size_t newI = printArrayCreationUsingLoop(startPos, array, i, _tmpSparseArrayValues); - - if (newI == i) { - // individual element assignment - _code << _indentation << auxArrayName_ << "[" << i << "] = "; - print(args[i]); - _code << "; "; - // print indexes (location of values) - _code << _C_SPARSE_INDEX_ARRAY << "["; - if (startPos != 0) _code << startPos << "+"; - _code << i << "] = " << info[i + 1] << ";\n"; - - _tmpSparseArrayValues[startPos + i] = &args[i]; - - } else { - // print indexes (location of values) - for (size_t j = i; j < newI; j++) { - _code << _indentation << _C_SPARSE_INDEX_ARRAY << "["; - if (startPos != 0) _code << startPos << "+"; - _code << j << "] = " << info[j + 1] << ";\n"; - } - - i = newI - 1; - } - - - } else { - // print indexes (location of values) - _code << _indentation - << _C_SPARSE_INDEX_ARRAY << "["; - if (startPos != 0) _code << startPos << "+"; - _code << i << "] = " << info[i + 1] << ";\n"; - } - - } -} - -template -inline size_t LanguageC::printArrayCreationUsingLoop(size_t startPos, - OperationNode& array, - size_t starti, - std::vector*>& tmpArrayValues) { - const std::vector >& args = array.getArguments(); - const size_t argSize = args.size(); - size_t i = starti + 1; - - std::ostringstream arrayAssign; - - const Argument& ref = args[starti]; - if (ref.getOperation() != nullptr) { - // - const OperationNode& refOp = *ref.getOperation(); - CGOpCode op = refOp.getOperationType(); - if (op == CGOpCode::Inv) { - /** - * from independents array - */ - for (; i < argSize; i++) { - if (isSameArgument(args[i], tmpArrayValues[startPos + i])) - break; // no assignment needed - - if (args[i].getOperation() == nullptr || - args[i].getOperation()->getOperationType() != CGOpCode::Inv || - !_nameGen->isConsecutiveInIndepArray(*args[i - 1].getOperation(), getVariableID(*args[i - 1].getOperation()), - *args[i].getOperation(), getVariableID(*args[i].getOperation()))) { - break; - } - } - - if (i - starti < 3) - return starti; - - // use loop - const std::string& indep = _nameGen->getIndependentArrayName(refOp, getVariableID(refOp)); - size_t start = _nameGen->getIndependentArrayIndex(refOp, getVariableID(refOp)); - long offset = long(start) - starti; - if (offset == 0) - arrayAssign << indep << "[i]"; - else - arrayAssign << indep << "[" << offset << " + i]"; - - } else if (op == CGOpCode::LoopIndexedIndep) { - /** - * from independents array in a loop - */ - size_t pos = refOp.getInfo()[1]; - IndexPattern* refIp = _info->loopIndependentIndexPatterns[pos]; - - LinearIndexPattern* refLIp = nullptr; - SectionedIndexPattern* refSecp = nullptr; - - if (refIp->getType() == IndexPatternType::Linear) { - refLIp = static_cast (refIp); - } else if (refIp->getType() == IndexPatternType::Sectioned) { - refSecp = static_cast (refIp); - } else { - return starti; // cannot determine consecutive elements - } - - for (; i < argSize; i++) { - if (isSameArgument(args[i], tmpArrayValues[startPos + i])) - break; // no assignment needed - - if (args[i].getOperation() == nullptr || - args[i].getOperation()->getOperationType() != CGOpCode::LoopIndexedIndep) { - break; // not an independent index pattern - } - - if (!_nameGen->isInSameIndependentArray(refOp, getVariableID(refOp), - *args[i].getOperation(), getVariableID(*args[i].getOperation()))) - break; - - pos = args[i].getOperation()->getInfo()[1]; - const IndexPattern* ip = _info->loopIndependentIndexPatterns[pos]; - - if (!isOffsetBy(ip, refIp, long(i) - long(starti))) { - break; // different pattern type - } - } - - if (i - starti < 3) - return starti; - - std::unique_ptr p2dip; - if (refLIp != nullptr) { - p2dip.reset(encapsulateIndexPattern(*refLIp, starti)); - } else { - assert(refSecp != nullptr); - p2dip.reset(encapsulateIndexPattern(*refSecp, starti)); - } - - std::unique_ptr> op2(OperationNode::makeTemporaryNode(CGOpCode::LoopIndexedIndep, refOp.getInfo(), refOp.getArguments())); - op2->getInfo()[1] = std::numeric_limits::max(); // just to be safe (this would be the index pattern id in the handler) - op2->getArguments().push_back(_info->auxIterationIndexOp); - - arrayAssign << _nameGen->generateIndexedIndependent(*op2, 0, *p2dip); - } else if (getVariableID(refOp) >= this->_minTemporaryVarID && op != CGOpCode::LoopIndexedDep && op != CGOpCode::LoopIndexedTmp && op != CGOpCode::Tmp) { - /** - * from temporary variable array - */ - for (; i < argSize; i++) { - if (isSameArgument(args[i], tmpArrayValues[startPos + i])) - break; // no assignment needed - else if (args[i].getOperation() == nullptr) - break; - - const OperationNode& opNode2 = *args[i].getOperation(); - if (getVariableID(opNode2) < this->_minTemporaryVarID) - break; - - CGOpCode op2 = opNode2.getOperationType(); - if (op2 == CGOpCode::LoopIndexedIndep || op2 == CGOpCode::LoopIndexedDep || op2 == CGOpCode::LoopIndexedTmp || op2 == CGOpCode::Tmp) - break; - - if (!_nameGen->isConsecutiveInTemporaryVarArray(*args[i - 1].getOperation(), getVariableID(*args[i - 1].getOperation()), - *args[i].getOperation(), getVariableID(*args[i].getOperation()))) - break; - } - - if (i - starti < 3) - return starti; - - // use loop - const std::string& tmpName = _nameGen->getTemporaryVarArrayName(refOp, getVariableID(refOp)); - size_t start = _nameGen->getTemporaryVarArrayIndex(refOp, getVariableID(refOp)); - long offset = long(start) - starti; - if (offset == 0) - arrayAssign << tmpName << "[i]"; - else - arrayAssign << tmpName << "[" << offset << " + i]"; - - } else { - // no loop used - return starti; - } - } else { - /** - * constant value? - */ - const Base& value = *args[starti].getParameter(); - for (; i < argSize; i++) { - if (args[i].getParameter() == nullptr || *args[i].getParameter() != value) { - break; // not the same constant value - } - - const Argument* oldArg = tmpArrayValues[startPos + i]; - if (oldArg != nullptr && oldArg->getParameter() != nullptr && *oldArg->getParameter() == value) { - break; // values are the same (no need to redefine) - } - } - - if (i - starti < 3) - return starti; - - arrayAssign << value; - } - - /** - * print the loop - */ - _code << _indentation << "for(i = " << starti << "; i < " << i << "; i++) " - << auxArrayName_ << "[i] = " << arrayAssign.str() << ";\n"; - - /** - * update values in the global temporary array - */ - for (size_t ii = starti; ii < i; ii++) { - tmpArrayValues[startPos + ii] = &args[ii]; - } - - return i; -} - -template -inline std::string LanguageC::getTempArrayName(const OperationNode& op) { - if (op.getOperationType() == CGOpCode::ArrayCreation) - return _nameGen->generateTemporaryArray(op); - else - return _nameGen->generateTemporarySparseArray(op); -} - -template -void LanguageC::printArrayElementOp(OperationNode& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for array element operation"); - CPPADCG_ASSERT_KNOWN(op.getArguments()[0].getOperation() != nullptr, "Invalid argument for array element operation"); - CPPADCG_ASSERT_KNOWN(op.getInfo().size() == 1, "Invalid number of information indexes for array element operation"); - - OperationNode& arrayOp = *op.getArguments()[0].getOperation(); - std::string arrayName; - if (arrayOp.getOperationType() == CGOpCode::ArrayCreation) - arrayName = _nameGen->generateTemporaryArray(arrayOp, getVariableID(arrayOp)); - else - arrayName = _nameGen->generateTemporarySparseArray(arrayOp, getVariableID(arrayOp)); - - _code << "(" << arrayName << ")[" << op.getInfo()[0] << "]"; -} - -template -inline void LanguageC::printArrayStructInit(const std::string& dataArrayName, - size_t pos, - const std::vector*>& arrays, - size_t k) { - _ss.str(""); - _ss << dataArrayName << "[" << pos << "]"; - printArrayStructInit(_ss.str(), *arrays[k]); -} - -template -inline void LanguageC::printArrayStructInit(const std::string& dataArrayName, - OperationNode& array) { - const std::string& aName = createVariableName(array); - - // lets see what was the previous values in this array - auto itLast = _atomicFuncArrays.find(dataArrayName); - bool firstTime = itLast == _atomicFuncArrays.end() || itLast->second.scope != _info->scope[array]; - AtomicFuncArray& lastArray = firstTime ? _atomicFuncArrays[dataArrayName] : itLast->second; - - bool changed = false; - - // apply the differences - if (array.getOperationType() == CGOpCode::ArrayCreation) { - size_t size = array.getArguments().size(); - - if (size > 0) { - if (firstTime || aName != lastArray.data) { - _code << _indentation; - _code << dataArrayName << ".data = " << aName << "; "; - lastArray.data = aName; - changed = true; - } - } else { - if (firstTime || "NULL" != lastArray.data) { - if (!changed) _code << _indentation; - _code << dataArrayName << ".data = NULL; "; - lastArray.data = "NULL"; - changed = true; - } - } - - if (firstTime || size != lastArray.size) { - if (!changed) _code << _indentation; - _code << dataArrayName << ".size = " << size << "; "; - lastArray.size = size; - changed = true; - } - if (firstTime || lastArray.sparse) { - if (!changed) _code << _indentation; - _code << dataArrayName << ".sparse = " << false << ";"; - lastArray.sparse = false; - changed = true; - } - - } else { - CPPADCG_ASSERT_KNOWN(array.getOperationType() == CGOpCode::SparseArrayCreation, "Invalid node type"); - size_t nnz = array.getArguments().size(); - size_t size = array.getInfo()[0]; - - if (nnz > 0) { - if (firstTime || aName != lastArray.data) { - _code << _indentation; - _code << dataArrayName << ".data = " << aName << "; "; - lastArray.data = aName; - changed = true; - } - } else { - if (firstTime || "NULL" != lastArray.data) { - _code << _indentation; - _code << dataArrayName << ".data = NULL; "; - lastArray.data = "NULL"; - changed = true; - } - } - - if (firstTime || size != lastArray.size) { - if (!changed) _code << _indentation; - _code << dataArrayName << ".size = " << size << "; "; - lastArray.size = size; - changed = true; - } - if (firstTime || !lastArray.sparse) { - if (!changed) _code << _indentation; - _code << dataArrayName << ".sparse = " << true << "; "; - lastArray.sparse = true; - changed = true; - } - if (firstTime || nnz != lastArray.nnz) { - if (!changed) _code << _indentation; - _code << dataArrayName << ".nnz = " << nnz << "; "; - lastArray.nnz = nnz; - changed = true; - } - - if (nnz > 0) { - size_t id = getVariableID(array); - if (firstTime || id != lastArray.idx_id) { - if (!changed) _code << _indentation; - _code << dataArrayName << ".idx = &(" << _C_SPARSE_INDEX_ARRAY << "[" << (id - 1) << "]);"; - lastArray.idx_id = id; - changed = true; - } - } else { - lastArray.idx_id = std::numeric_limits::max(); - } - } - - lastArray.scope = _info->scope[array]; - - if (changed) - _code << "\n"; -} - -template -inline void LanguageC::markArrayChanged(OperationNode& ty) { - size_t id = getVariableID(ty); - size_t tySize = ty.getArguments().size(); - - if (ty.getOperationType() == CGOpCode::ArrayCreation) { - for (size_t i = 0; i < tySize; i++) { - _tmpArrayValues[id - 1 + i] = nullptr; - } - } else { - for (size_t i = 0; i < tySize; i++) { - _tmpSparseArrayValues[id - 1 + i] = nullptr; - } - } -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/c/language_c_double.hpp b/ct_core/include/ct/external/cppad/cg/lang/c/language_c_double.hpp deleted file mode 100644 index d5682f014..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/c/language_c_double.hpp +++ /dev/null @@ -1,41 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_C_DOUBLE_INCLUDED -#define CPPAD_CG_LANGUAGE_C_DOUBLE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Specialization of the C language function names for doubles - * - * @author Joao Leal - */ -template<> -inline const std::string& LanguageC::absFuncName() { - static const std::string name("fabs"); - return name; -} - -template<> -inline const std::string& LanguageC::getPrintfBaseFormat() { - static const std::string format("%f"); - return format; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/c/language_c_float.hpp b/ct_core/include/ct/external/cppad/cg/lang/c/language_c_float.hpp deleted file mode 100644 index d6441dd5d..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/c/language_c_float.hpp +++ /dev/null @@ -1,152 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_C_FLOAT_INCLUDED -#define CPPAD_CG_LANGUAGE_C_FLOAT_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2015 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Specialization of the C language function names for floats (requires C99) - * - * @author Joao Leal - */ -template<> -inline const std::string& LanguageC::absFuncName() { - static const std::string name("fabsf"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::acosFuncName() { - static const std::string name("acosf"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::asinFuncName() { - static const std::string name("asinf"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::atanFuncName() { - static const std::string name("atanf"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::coshFuncName() { - static const std::string name("coshf"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::cosFuncName() { - static const std::string name("cosf"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::expFuncName() { - static const std::string name("expf"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::logFuncName() { - static const std::string name("logf"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::sinhFuncName() { - static const std::string name("sinhf"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::sinFuncName() { - static const std::string name("sinf"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::sqrtFuncName() { - static const std::string name("sqrtf"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::tanhFuncName() { - static const std::string name("tanhf"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::tanFuncName() { - static const std::string name("tanf"); // C99 - return name; -} - -#if CPPAD_USE_CPLUSPLUS_2011 -template<> -inline const std::string& LanguageC::erfFuncName() { - static const std::string name("erff"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::asinhFuncName() { - static const std::string name("asinhf"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::acoshFuncName() { - static const std::string name("acoshf"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::atanhFuncName() { - static const std::string name("atanhf"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::expm1FuncName() { - static const std::string name("expm1f"); // C99 - return name; -} - -template<> -inline const std::string& LanguageC::log1pFuncName() { - static const std::string name("log1pf"); // C99 - return name; -} - -#endif - -template<> -inline const std::string& LanguageC::getPrintfBaseFormat() { - static const std::string format("%f"); - return format; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/c/language_c_index_patterns.hpp b/ct_core/include/ct/external/cppad/cg/lang/c/language_c_index_patterns.hpp deleted file mode 100644 index e63f34692..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/c/language_c_index_patterns.hpp +++ /dev/null @@ -1,442 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_C_INDEX_PATTERNS_INCLUDED -#define CPPAD_CG_LANGUAGE_C_INDEX_PATTERNS_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -inline void LanguageC::generateNames4RandomIndexPatterns(const std::set& randomPatterns) { - std::ostringstream os; - - std::set usedNames; - - // save existing names so that they are not to overridden - // (independent variable names might have already used them) - for (RandomIndexPattern* ip : randomPatterns) { - if (!ip->getName().empty()) { - usedNames.insert(ip->getName()); - } - } - - // create new names for the index pattern arrays without a name - size_t c = 0; - for (RandomIndexPattern* ip : randomPatterns) { - if (ip->getName().empty()) { - // new name required - std::string name; - do { - os << _C_STATIC_INDEX_ARRAY << c; - name = os.str(); - os.str(""); - c++; - } while (usedNames.find(name) != usedNames.end()); - - ip->setName(name); - } - } - -} - -template -inline void LanguageC::printRandomIndexPatternDeclaration(std::ostringstream& os, - const std::string& indentation, - const std::set& randomPatterns) { - for (RandomIndexPattern* ip : randomPatterns) { - if (ip->getType() == IndexPatternType::Random1D) { - /** - * 1D - */ - Random1DIndexPattern* ip1 = static_cast (ip); - const std::map& x2y = ip1->getValues(); - - std::vector y(x2y.rbegin()->first + 1); - for (const std::pair& p : x2y) - y[p.first] = p.second; - - os << indentation; - printStaticIndexArray(os, ip->getName(), y); - } else { - CPPADCG_ASSERT_UNKNOWN(ip->getType() == IndexPatternType::Random2D); - /** - * 2D - */ - Random2DIndexPattern* ip2 = static_cast (ip); - os << indentation; - printStaticIndexMatrix(os, ip->getName(), ip2->getValues()); - } - } -} - -template -inline void LanguageC::createIndexDeclaration() { - if (_info == nullptr) - return; - - if (_info->indexes.empty()) - return; - - std::set*> funcArgs(_funcArgIndexes.begin(), _funcArgIndexes.end()); - - bool first = true; - - printRandomIndexPatternDeclaration(_ss, _spaces, _info->indexRandomPatterns); - - _ss << _spaces << U_INDEX_TYPE; - for (const OperationNode* iti : _info->indexes) { - - if (funcArgs.find(iti) == funcArgs.end()) { - if (first) first = false; - else _ss << ","; - - _ss << " " << (*iti->getName()); - } - - } - _ss << ";\n"; -} - -template -void LanguageC::printStaticIndexArray(std::ostringstream& os, - const std::string& name, - const std::vector& values) { - os << "static " << U_INDEX_TYPE << " const " << name << "[" << values.size() << "] = {"; - if (!values.empty()) { - os << values[0]; - for (size_t i = 1; i < values.size(); i++) { - os << "," << values[i]; - } - } - os << "};\n"; -} - -template -void LanguageC::printStaticIndexMatrix(std::ostringstream& os, - const std::string& name, - const std::map >& values) { - size_t m = 0; - size_t n = 0; - - std::map >::const_iterator it; - std::map::const_iterator ity2z; - - if (!values.empty()) { - m = values.rbegin()->first + 1; - - for (it = values.begin(); it != values.end(); ++it) { - if (!it->second.empty()) - n = std::max(n, it->second.rbegin()->first + 1); - } - } - - os << "static " << U_INDEX_TYPE << " const " << name << "[" << m << "][" << n << "] = {"; - size_t x = 0; - for (it = values.begin(); it != values.end(); ++it) { - if (it->first != x) { - while (it->first != x) { - os << "{},"; - x++; - } - } - - os << "{"; - - size_t y = 0; - for (ity2z = it->second.begin(); ity2z != it->second.end(); ++ity2z) { - if (ity2z->first != y) { - while (ity2z->first != y) { - os << "0,"; - y++; - } - } - - os << ity2z->second; - if (ity2z->first != it->second.rbegin()->first) os << ","; - - y++; - } - - os << "}"; - if (it->first != values.rbegin()->first) os << ","; - - x++; - } - os << "};\n"; -} - -template -inline std::string LanguageC::indexPattern2String(const IndexPattern& ip, - const OperationNode& index) { - return indexPattern2String(ip,{index.getName()}); -} - -template -inline std::string LanguageC::indexPattern2String(const IndexPattern& ip, - const std::string& index) { - return indexPattern2String(ip,{&index}); -} - -template -inline std::string LanguageC::indexPattern2String(const IndexPattern& ip, - const std::vector*>& indexes) { - std::vector indexStr(indexes.size()); - for (size_t i = 0; i < indexes.size(); ++i) - indexStr[i] = indexes[i]->getName(); - return indexPattern2String(ip, indexStr); -} - -template -inline std::string LanguageC::indexPattern2String(const IndexPattern& ip, - const std::vector& indexes) { - std::stringstream ss; - switch (ip.getType()) { - case IndexPatternType::Linear: // y = x * a + b - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 1, "Invalid number of indexes"); - const LinearIndexPattern& lip = static_cast (ip); - return linearIndexPattern2String(lip, *indexes[0]); - } - case IndexPatternType::Sectioned: - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 1, "Invalid number of indexes"); - const SectionedIndexPattern* lip = static_cast (&ip); - const std::map& sections = lip->getLinearSections(); - size_t sSize = sections.size(); - CPPADCG_ASSERT_UNKNOWN(sSize > 1); - - std::map::const_iterator its = sections.begin(); - for (size_t s = 0; s < sSize - 1; s++) { - const IndexPattern* lp = its->second; - ++its; - size_t xStart = its->first; - - ss << "(" << (*indexes[0]) << "<" << xStart << ")? " - << indexPattern2String(*lp, *indexes[0]) << ": "; - } - ss << indexPattern2String(*its->second, *indexes[0]); - - return ss.str(); - } - - case IndexPatternType::Plane2D: // y = f(x) + f(z) - { - CPPADCG_ASSERT_KNOWN(indexes.size() >= 1, "Invalid number of indexes"); - std::string indexExpr; - const Plane2DIndexPattern& pip = static_cast (ip); - bool useParens = pip.getPattern1() != nullptr && pip.getPattern2() != nullptr; - - if (useParens) indexExpr += "("; - - if (pip.getPattern1() != nullptr) - indexExpr += indexPattern2String(*pip.getPattern1(), *indexes[0]); - - if (useParens) indexExpr += ") + ("; - - if (pip.getPattern2() != nullptr) - indexExpr += indexPattern2String(*pip.getPattern2(), *indexes.back()); - - if (useParens) indexExpr += ")"; - - return indexExpr; - } - case IndexPatternType::Random1D: - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 1, "Invalid number of indexes"); - const Random1DIndexPattern& rip = static_cast (ip); - CPPADCG_ASSERT_KNOWN(!rip.getName().empty(), "Invalid name for array"); - return rip.getName() + "[" + (*indexes[0]) + "]"; - } - case IndexPatternType::Random2D: - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 2, "Invalid number of indexes"); - const Random2DIndexPattern& rip = static_cast (ip); - CPPADCG_ASSERT_KNOWN(!rip.getName().empty(), "Invalid name for array"); - return rip.getName() + "[" + (*indexes[0]) + "][" + (*indexes[1]) + "]"; - } - default: - CPPADCG_ASSERT_UNKNOWN(false); // should never reach this - return ""; - } -} - -template -inline std::string LanguageC::linearIndexPattern2String(const LinearIndexPattern& lip, - const OperationNode& index) { - return linearIndexPattern2String(lip, *index.getName()); -} - -template -inline std::string LanguageC::linearIndexPattern2String(const LinearIndexPattern& lip, - const std::string& index) { - long dy = lip.getLinearSlopeDy(); - long dx = lip.getLinearSlopeDx(); - long b = lip.getLinearConstantTerm(); - long xOffset = lip.getXOffset(); - - std::stringstream ss; - if (dy != 0) { - if (xOffset != 0) { - ss << "("; - } - ss << index; - if (xOffset != 0) { - ss << " - " << xOffset << ")"; - } - - if (dx != 1) { - ss << " / " << dx; - } - if (dy != 1) { - ss << " * " << dy; - } - } else if (b == 0) { - ss << "0"; // when dy == 0 and b == 0 - } - - if (b != 0) { - if (dy != 0) - ss << " + "; - ss << b; - } - return ss.str(); -} - -template -bool LanguageC::isOffsetBy(const IndexPattern* ip, - const IndexPattern* refIp, - long offset) { - - if (ip->getType() == IndexPatternType::Linear) { - const LinearIndexPattern* lIp = dynamic_cast (ip); - assert(lIp != nullptr); - - if (refIp->getType() == IndexPatternType::Linear) - return false; - const LinearIndexPattern* refLIp = dynamic_cast (refIp); - assert(refLIp != nullptr); - - return isOffsetBy(*lIp, *refLIp, offset); - - } else if (ip->getType() == IndexPatternType::Sectioned) { - const SectionedIndexPattern* sIp = dynamic_cast (ip); - assert(sIp != nullptr); - - if (refIp->getType() != IndexPatternType::Sectioned) - return false; - const SectionedIndexPattern* refSecp = dynamic_cast (refIp); - assert(refSecp != nullptr); - - return isOffsetBy(*sIp, *refSecp, offset); - - - } else { - return false; // different pattern type - } -} - -template -bool LanguageC::isOffsetBy(const LinearIndexPattern* lIp, - const LinearIndexPattern* refLIp, - long offset) { - - if (lIp == nullptr || refLIp == nullptr) - return false; // different pattern type - - return isOffsetBy(*lIp, *refLIp, offset); -} - -template -bool LanguageC::isOffsetBy(const LinearIndexPattern& lIp, - const LinearIndexPattern& refLIp, - long offset) { - return refLIp.getLinearSlopeDx() == lIp.getLinearSlopeDx() && - refLIp.getLinearSlopeDy() == lIp.getLinearSlopeDy() && - refLIp.getXOffset() == lIp.getXOffset() && - refLIp.getLinearConstantTerm() + offset == lIp.getLinearConstantTerm(); -} - -template -bool LanguageC::isOffsetBy(const SectionedIndexPattern* sIp, - const SectionedIndexPattern* refSecp, - long offset) { - if (refSecp == nullptr || sIp == nullptr) - return false; // different pattern type - - return isOffsetBy(*sIp, *refSecp, offset); -} - -template -bool LanguageC::isOffsetBy(const SectionedIndexPattern& sIp, - const SectionedIndexPattern& refSecp, - long offset) { - - if (refSecp.getLinearSections().size() != sIp.getLinearSections().size()) - return false; // different pattern type - - auto itRef = refSecp.getLinearSections().begin(); - for (const auto& section : sIp.getLinearSections()) { - - if (itRef->first != section.first) { - return false; // different pattern type - } else if (itRef->second->getType() != IndexPatternType::Linear || section.second->getType() != IndexPatternType::Linear) { - return false; // unable to handle this now, consider different patterns - } - - LinearIndexPattern* refSecLIp = static_cast (itRef->second); - LinearIndexPattern* secLIp = static_cast (section.second); - - if (!isOffsetBy(secLIp, refSecLIp, offset)) { - return false; // different pattern type - } - - ++itRef; - } - - return true; -} - -template -Plane2DIndexPattern* LanguageC::encapsulateIndexPattern(const LinearIndexPattern& refLIp, - size_t starti) { - std::unique_ptr ip2; - - LinearIndexPattern* lip2 = new LinearIndexPattern(refLIp); - ip2.reset(lip2); - lip2->setLinearConstantTerm(lip2->getLinearConstantTerm() - starti); - - return new Plane2DIndexPattern(ip2.release(), new LinearIndexPattern(0, 1, 1, 0)); -} - -template -Plane2DIndexPattern* LanguageC::encapsulateIndexPattern(const SectionedIndexPattern& refSecp, - size_t starti) { - std::unique_ptr ip2; - - std::map sections; - for (const auto& section : refSecp.getLinearSections()) { - LinearIndexPattern* lip2 = new LinearIndexPattern(*static_cast (section.second)); - lip2->setLinearConstantTerm(lip2->getLinearConstantTerm() - starti); - sections[section.first] = lip2; - } - ip2.reset(new SectionedIndexPattern(sections)); - - return new Plane2DIndexPattern(ip2.release(), new LinearIndexPattern(0, 1, 1, 0)); -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/c/language_c_loops.hpp b/ct_core/include/ct/external/cppad/cg/lang/c/language_c_loops.hpp deleted file mode 100644 index 461441ef9..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/c/language_c_loops.hpp +++ /dev/null @@ -1,178 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_C_LOOPS_INCLUDED -#define CPPAD_CG_LANGUAGE_C_LOOPS_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2015 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -void LanguageC::printLoopIndexedDep(OperationNode& node) { - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 1, "Invalid number of arguments for loop indexed dependent operation"); - - // LoopIndexedDep - print(node.getArguments()[0]); -} - -template -size_t LanguageC::printLoopIndexDeps(const std::vector*>& variableOrder, - size_t pos) { - CPPADCG_ASSERT_KNOWN(pos < variableOrder.size(), "Invalid number of arguments for array creation operation"); - CPPADCG_ASSERT_KNOWN(variableOrder[pos]->getOperationType() == CGOpCode::LoopIndexedDep, "Invalid operation type"); - - const size_t vSize = variableOrder.size(); - - for (size_t i = pos; i < vSize; i++) { - if (variableOrder[i]->getOperationType() != CGOpCode::LoopIndexedDep) { - return i - 1; - } - - // try to use a loop for element assignment - size_t newI = printLoopIndexedDepsUsingLoop(variableOrder, i); - - if (newI == i) { - // individual element assignment - printAssigment(*variableOrder[i]); - } else { - i = newI; - } - } - - return vSize - 1; -} - -template -inline size_t LanguageC::printLoopIndexedDepsUsingLoop(const std::vector*>& variableOrder, - size_t starti) { - CPPADCG_ASSERT_KNOWN(variableOrder[starti] != nullptr, "Invalid node"); - CPPADCG_ASSERT_KNOWN(variableOrder[starti]->getOperationType() == CGOpCode::LoopIndexedDep, "Invalid operation type"); - - const size_t vSize = variableOrder.size(); - - const OperationNode& ref = *variableOrder[starti]; - - const IndexPattern* refIp = _info->loopDependentIndexPatterns[ref.getInfo()[0]]; - size_t refAssignOrAdd = ref.getInfo()[1]; - - /** - * Check that the assigned value is from an array - */ - const OperationNode* refLeft = ref.getArguments()[0].getOperation(); - if (refLeft == nullptr) { - return starti; - } else if (refLeft->getOperationType() != CGOpCode::ArrayElement) { - return starti; - } - - /** - * check that the type of index pattern can be used within a loop - */ - const LinearIndexPattern* refLIp = nullptr; - const SectionedIndexPattern* refSecp = nullptr; - - if (refIp->getType() == IndexPatternType::Linear) { - refLIp = static_cast (refIp); - } else if (refIp->getType() == IndexPatternType::Sectioned) { - refSecp = static_cast (refIp); - } else { - return starti; // cannot determine consecutive elements - } - - /** - * Find last compatible variable in variableOrder - */ - const OperationNode* refArray = refLeft->getArguments()[0].getOperation(); - const size_t startArrayIndex = refLeft->getInfo()[0]; - - size_t i = starti + 1; - - for (; i < vSize; i++) { - OperationNode* node = variableOrder[i]; - if (node->getOperationType() != CGOpCode::LoopIndexedDep) - break; - - const OperationNode* nodeLeft = variableOrder[i]->getArguments()[0].getOperation(); - if (nodeLeft->getOperationType() != CGOpCode::ArrayElement) - break; - - const OperationNode* arrayi = nodeLeft->getArguments()[0].getOperation(); - if (arrayi != refArray) - break; - - long offset = long(i) - long(starti); - - if (nodeLeft->getInfo()[0] != startArrayIndex + offset) - break; - - if (node->getInfo()[1] != refAssignOrAdd) - break; - - const IndexPattern* ip = _info->loopDependentIndexPatterns[node->getInfo()[0]]; - if (!isOffsetBy(ip, refIp, offset)) { - break; // different pattern type - } - } - - if (i - starti < 3) - return starti; // no point in looping for 2 elements - - /** - * Create the dependent variable name with the new index pattern - */ - std::unique_ptr p2dip; - if (refLIp != nullptr) { - p2dip.reset(encapsulateIndexPattern(*refLIp, 0)); - } else { - assert(refSecp != nullptr); - p2dip.reset(encapsulateIndexPattern(*refSecp, 0)); - } - - std::unique_ptr> op2(OperationNode::makeTemporaryNode(CGOpCode::LoopIndexedDep, ref.getInfo(), ref.getArguments())); - op2->getInfo()[1] = std::numeric_limits::max(); // just to be safe (this would be the index pattern id in the handler) - op2->getArguments().push_back(_info->auxIterationIndexOp); - - std::ostringstream rightAssign; - - rightAssign << _nameGen->generateIndexedDependent(*op2, 0, *p2dip); - - /** - * print the loop - */ - size_t depVarCount = i - starti; - _code << _indentation << "for(i = 0; i < " << depVarCount << "; i++) "; - _code << rightAssign.str() << " "; - if (refAssignOrAdd == 1) { - _code << "+="; - } else { - _code << _depAssignOperation; - } - _code << " "; - - std::string arrayName; - if (refArray->getOperationType() == CGOpCode::ArrayCreation) - arrayName = _nameGen->generateTemporaryArray(*refArray, getVariableID(*refArray)); - else - arrayName = _nameGen->generateTemporarySparseArray(*refArray, getVariableID(*refArray)); - - _code << "(" << arrayName << ")[i + " << startArrayIndex << "];\n"; - - return i - 1; -} - - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/dot/dot.hpp b/ct_core/include/ct/external/cppad/cg/lang/dot/dot.hpp deleted file mode 100644 index b9273432e..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/dot/dot.hpp +++ /dev/null @@ -1,25 +0,0 @@ -#ifndef CPPAD_CG_DOT_INCLUDED -#define CPPAD_CG_DOT_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -// --------------------------------------------------------------------------- -// dot source code generation -#include -#include -#include -#include - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/dot/dot_util.hpp b/ct_core/include/ct/external/cppad/cg/lang/dot/dot_util.hpp deleted file mode 100644 index abee38354..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/dot/dot_util.hpp +++ /dev/null @@ -1,60 +0,0 @@ -#ifndef CPPAD_CG_DOT_UTIL_INCLUDED -#define CPPAD_CG_DOT_UTIL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include - -namespace CppAD { -namespace cg { - -/** - * Prints the graph resulting in a single dependent variable. - */ -template -inline void printDotExpression(CG& dep, - std::ostream& out = std::cout) { - if (dep.getOperationNode() != nullptr) { - if (dep.getOperationNode()->getCodeHandler() == nullptr) { - throw CGException("Unable to print expression: found an operation node without a CodeHandler!"); - } - - CodeHandler& handler = *dep.getOperationNode()->getCodeHandler(); - LanguageDot langDot; - LangCDefaultVariableNameGenerator nameGen; - - std::vector > depv(1); - depv[0] = dep; - - std::ostringstream code; - handler.generateCode(code, langDot, depv, nameGen); - out << code.str(); - } else { - out << "digraph {\n" - "\"" << dep.getValue() << "\" -> \"y[0]\"\n" - "}" << std::endl; - } -} - -template -inline void printDotExpression(OperationNode& dep, - std::ostream& out = std::cout) { - printDotExpression(CG(dep), out); -} - -} -} - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/dot/language_dot.hpp b/ct_core/include/ct/external/cppad/cg/lang/dot/language_dot.hpp deleted file mode 100644 index ccdb620d5..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/dot/language_dot.hpp +++ /dev/null @@ -1,1458 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_DOT_INCLUDED -#define CPPAD_CG_LANGUAGE_DOT_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Generates the model using the dot language used by graphviz. - * - * @author Joao Leal - */ -template -class LanguageDot : public Language { -protected: - static const std::string _C_STATIC_INDEX_ARRAY; - static const std::string _C_SPARSE_INDEX_ARRAY; -protected: - // information from the code handler (not owned) - LanguageGenerationData * _info; - // new line characters - std::string _endline; - // output stream for the generated source code - std::ostringstream _code; - // creates the variable names - VariableNameGenerator * _nameGen; - // auxiliary string stream - std::ostringstream _ss; - // - size_t _independentSize; - // - size_t _minTemporaryVarID; - // maps the variable IDs to the their position in the dependent vector - // (some IDs may be the same as the independent variables when dep = indep) - std::map _dependentIDs; - // the dependent variable vector - const ArrayWrapper >* _dependent; - // whether or not to ignore assignment of constant zero values to dependent variables - bool _ignoreZeroDepAssign; - // the name of the file to be created without the extension - std::string _filename; - // - std::vector*> _currentLoops; - // the maximum precision used to print values - size_t _parameterPrecision; - // - bool _combineParameterNodes; - // - std::string _indepNodeStyle; - // - std::string _depNodeStyle; -private: - std::vector varIds_; - size_t parIdx_; -public: - - /** - * Creates a MathML language source code generator - */ - LanguageDot() : - _info(nullptr), - _endline("\n"), - _nameGen(nullptr), - _independentSize(0), // not really required (but it avoids warnings) - _minTemporaryVarID(0), // not really required (but it avoids warnings) - _dependent(nullptr), - _ignoreZeroDepAssign(false), - _filename("algorithm"), - _parameterPrecision(std::numeric_limits::digits10), - _combineParameterNodes(true), - parIdx_(0) { // not really required (but it avoids warnings) - } - - inline virtual ~LanguageDot() { - } - - inline bool isIgnoreZeroDepAssign() const { - return _ignoreZeroDepAssign; - } - - inline void setIgnoreZeroDepAssign(bool ignore) { - _ignoreZeroDepAssign = ignore; - } - - inline void setFilename(const std::string& name) { - _filename = name; - } - - /** - * Provides the maximum precision used to print constant values in the - * generated source code - * - * @return the maximum number of digits - */ - virtual size_t getParameterPrecision() const { - return _parameterPrecision; - } - - /** - * Defines the maximum precision used to print constant values in the - * generated source code - * - * @param p the maximum number of digits - */ - virtual void setParameterPrecision(size_t p) { - _parameterPrecision = p; - } - - /** - * Defines the style for the independent variable nodes - */ - inline void setIndepNodeStyle(const std::string& indepNodeStyle) { - _indepNodeStyle = indepNodeStyle; - } - - /** - * Provides the style for the independent variable nodes - */ - inline const std::string& getIndepNodeStyle() const { - return _indepNodeStyle; - } - - /** - * Defines the style for the dependent variable nodes - */ - inline void setDepNodeStyle(const std::string& depNodeStyle) { - _depNodeStyle = depNodeStyle; - } - - /** - * Provides the style for the dependent variable nodes - */ - inline const std::string& getDepNodeStyle() const { - return _depNodeStyle; - } - - /** - * - */ - inline void setCombineParameterNodes(bool combineParameterNodes) { - _combineParameterNodes = combineParameterNodes; - } - - /** - * - */ - inline bool isCombineParameterNodes() const { - return _combineParameterNodes; - } - - /*************************************************************************** - * STATIC - **************************************************************************/ - static inline void printIndexCondExpr(std::ostringstream& out, - const std::vector& info, - const std::string& index) { - CPPADCG_ASSERT_KNOWN(info.size() > 1 && info.size() % 2 == 0, "Invalid number of information elements for an index condition expression operation"); - - size_t infoSize = info.size(); - for (size_t e = 0; e < infoSize; e += 2) { - if (e > 0) { - out << " or "; // or - } - size_t min = info[e]; - size_t max = info[e + 1]; - if (min == max) { - out << index << "==" << min; - } else if (min == 0) { - out << index << "≤" << max; - } else if (max == std::numeric_limits::max()) { - out << min << "≤" << index; - } else { - if (infoSize != 2) - out << "("; - - if (max - min == 1) - out << min << "==" << index << " or " << index << "==" << max; - else - out << min << "≤" << index << " and " << index << "≤" << max; - - if (infoSize != 2) - out << ")"; - } - } - } - - /*************************************************************************** - * - **************************************************************************/ - - inline void printStaticIndexArray(std::ostringstream& os, - const std::string& name, - const std::vector& values); - - inline void printStaticIndexMatrix(std::ostringstream& os, - const std::string& name, - const std::map >& values); - - /*************************************************************************** - * index patterns - **************************************************************************/ - static inline void generateNames4RandomIndexPatterns(const std::set& randomPatterns); - - inline void printRandomIndexPatternDeclaration(std::ostringstream& os, - const std::set& randomPatterns); - - static void indexPattern2String(std::ostream& os, - const IndexPattern& ip, - const OperationNode& index); - - static void indexPattern2String(std::ostream& os, - const IndexPattern& ip, - const std::vector*>& indexes); - - static inline void linearIndexPattern2String(std::ostream& os, - const LinearIndexPattern& lip, - const OperationNode& index); - - /*************************************************************************** - * protected - **************************************************************************/ -protected: - - virtual void generateSourceCode(std::ostream& out, - const std::unique_ptr >& info) override { - // clean up - _code.str(""); - _ss.str(""); - _currentLoops.clear(); - parIdx_ = 0; - - // save some info - _info = info.get(); - _independentSize = info->independent.size(); - _dependent = &info->dependent; - _nameGen = &info->nameGen; - _minTemporaryVarID = info->minTemporaryVarID; - const ArrayWrapper >& dependent = info->dependent; - const std::vector*>& variableOrder = info->variableOrder; - - varIds_.resize(_minTemporaryVarID + variableOrder.size()); - std::fill(varIds_.begin(), varIds_.end(), 0); - - _code << "digraph {" << _endline << _endline; - - /** - * generate index array names (might be used for variable names) - */ - generateNames4RandomIndexPatterns(info->indexRandomPatterns); - - /** - * generate variable names - */ - //generate names for the independent variables - _code << "subgraph indep {" << _endline; - _code << " rank=min" << _endline; - if(!_indepNodeStyle.empty()) { - _code << "node [" << _indepNodeStyle << "]" << _endline; - } - for (size_t j = 0; j < _independentSize; j++) { - OperationNode& op = *info->independent[j]; - - _code << " v" << op.getHandlerPosition() << " [label=\""; - if (op.getName() == nullptr) { - _code << _nameGen->generateIndependent(op, getVariableID(op)); - } else { - _code << *op.getName(); - } - _code << "\"]" << _endline; - - } - _code << "}" << _endline; - - // generate names for the dependent variables (must be after naming independents) - _code << "subgraph dep {" << _endline; - _code << " rank=max" << _endline; - if(!_depNodeStyle.empty()) { - _code << "node [" << _depNodeStyle << "]" << _endline; - } - for (size_t i = 0; i < dependent.size(); i++) { - - OperationNode* node = dependent[i].getOperationNode(); - if (node != nullptr && node->getOperationType() != CGOpCode::LoopEnd) { - _code << " y" << i << " [label=\""; - if(node->getName() == nullptr) { - if (node->getOperationType() == CGOpCode::LoopIndexedDep) { - size_t pos = node->getInfo()[0]; - const IndexPattern* ip = info->loopDependentIndexPatterns[pos]; - _code << _nameGen->generateIndexedDependent(*node, getVariableID(*node), *ip); - - } else { - _code << _nameGen->generateDependent(i); - } - } else { - _code << *node->getName(); - } - _code << "\"]" << _endline; - } - } - _code << "}" << _endline; - - - /** - * Loop indexes - */ - printRandomIndexPatternDeclaration(_ss, _info->indexRandomPatterns); - - /** - * function variable declaration - */ - const std::vector& indArg = _nameGen->getIndependent(); - const std::vector& depArg = _nameGen->getDependent(); - const std::vector& tmpArg = _nameGen->getTemporary(); - CPPADCG_ASSERT_KNOWN(indArg.size() > 0 && depArg.size() > 0, - "There must be at least one dependent and one independent argument"); - CPPADCG_ASSERT_KNOWN(tmpArg.size() == 3, - "There must be three temporary variables"); - - /** - * Determine the dependent variables that result from the same operations - */ - // dependent variables indexes that are copies of other dependent variables - std::set dependentDuplicates; - - for (size_t i = 0; i < dependent.size(); i++) { - OperationNode* node = dependent[i].getOperationNode(); - if (node != nullptr) { - CGOpCode type = node->getOperationType(); - if (type != CGOpCode::Inv && type != CGOpCode::LoopEnd) { - size_t varID = getVariableID(*node); - if (varID > 0) { - std::map::const_iterator it2 = _dependentIDs.find(varID); - if (it2 == _dependentIDs.end()) { - _dependentIDs[getVariableID(*node)] = i; - } else { - // there can be several dependent variables with the same ID - dependentDuplicates.insert(i); - } - } - } - } - } - - /** - * non-constant variables - */ - if (variableOrder.size() > 0) { - // generate names for temporary variables - for (OperationNode* node : variableOrder) { - CGOpCode op = node->getOperationType(); - if (!isDependent(*node) && op != CGOpCode::IndexDeclaration) { - // variable names for temporaries must always be created since they might have been used before with a different name/id - if (requiresVariableName(*node) && op != CGOpCode::ArrayCreation && op != CGOpCode::SparseArrayCreation) { - node->setName(_nameGen->generateTemporary(*node, getVariableID(*node))); - } else if (op == CGOpCode::ArrayCreation) { - node->setName(_nameGen->generateTemporaryArray(*node, getVariableID(*node))); - } else if (op == CGOpCode::SparseArrayCreation) { - node->setName(_nameGen->generateTemporarySparseArray(*node, getVariableID(*node))); - } - } - } - - /** - * Source code generation magic! - */ - for (OperationNode* it : variableOrder) { - // check if a new function should start - OperationNode& node = *it; - - // a dependent variable assigned by a loop does require any source code (its done inside the loop) - if (node.getOperationType() == CGOpCode::DependentRefRhs) { - continue; // nothing to do (this operation is right hand side only) - } else if (node.getOperationType() == CGOpCode::TmpDcl) { // temporary variable declaration does not need any source code here - continue; // nothing to do (bogus operation) - } - - printExpressionNoVarCheck(node); - } - - } - - // dependent duplicates - if (dependentDuplicates.size() > 0) { - _code << "// variable duplicates: " << dependentDuplicates.size() << _endline; - - for (size_t index : dependentDuplicates) { - const CG& dep = dependent[index]; - OperationNode* depNode = dep.getOperationNode(); - - _code << makeNodeName(*depNode); - _code << " -> y" << index; - _code << _endline; - } - } - - for (size_t i = 0; i < dependent.size(); i++) { - if (!dependent[i].isParameter() && dependent[i].getOperationNode()->getOperationType() != CGOpCode::Inv) { - _code << makeNodeName(*dependent[i].getOperationNode()); - _code << " -> y" << i; - _code << _endline; - } - } - - // constant dependent variables - bool commentWritten = false; - for (size_t i = 0; i < dependent.size(); i++) { - if (dependent[i].isParameter()) { - if (!_ignoreZeroDepAssign || !dependent[i].isIdenticalZero()) { - if (!commentWritten) { - _code << "// dependent variables without operations" << _endline; - commentWritten = true; - } - - _code << makeNodeName(dependent[i].getValue()); - _code << " -> y" << i; - _code << _endline; - } - } else if (dependent[i].getOperationNode()->getOperationType() == CGOpCode::Inv) { - if (!commentWritten) { - _code << "// dependent variables without operations" << _endline; - commentWritten = true; - } - - _code << makeNodeName(*dependent[i].getOperationNode()); - _code << " -> y" << i; - _code << _endline; - } - } - - _code << _endline << "}" << _endline; // digraph - - // a single source file - out << _code.str(); - } - - inline size_t getVariableID(const OperationNode& node) const { - return _info->varId[node]; - } - - virtual bool createsNewVariable(const OperationNode& var, - size_t totalUseCount) const override { - CGOpCode op = var.getOperationType(); - if (totalUseCount > 1) { - return op != CGOpCode::ArrayElement && op != CGOpCode::Index && op != CGOpCode::IndexDeclaration && op != CGOpCode::Tmp; - } else { - return (op == CGOpCode::ArrayCreation || - op == CGOpCode::SparseArrayCreation || - op == CGOpCode::AtomicForward || - op == CGOpCode::AtomicReverse || - op == CGOpCode::ComLt || - op == CGOpCode::ComLe || - op == CGOpCode::ComEq || - op == CGOpCode::ComGe || - op == CGOpCode::ComGt || - op == CGOpCode::ComNe || - op == CGOpCode::LoopIndexedDep || - op == CGOpCode::LoopIndexedTmp || - op == CGOpCode::IndexAssign || - op == CGOpCode::Assign) && - op != CGOpCode::CondResult; - } - } - - virtual bool requiresVariableName(const OperationNode& var) const { - CGOpCode op = var.getOperationType(); - return (_info->totalUseCount.get(var) > 1 && - op != CGOpCode::AtomicForward && - op != CGOpCode::AtomicReverse && - op != CGOpCode::LoopStart && - op != CGOpCode::LoopEnd && - op != CGOpCode::Index && - op != CGOpCode::IndexAssign && - op != CGOpCode::StartIf && - op != CGOpCode::ElseIf && - op != CGOpCode::Else && - op != CGOpCode::EndIf && - op != CGOpCode::CondResult && - op != CGOpCode::LoopIndexedTmp && - op != CGOpCode::Tmp); - } - - /** - * Whether or not this operation assign its expression to a variable by - * itself. - * - * @param var the operation node - * @return - */ - virtual bool directlyAssignsVariable(const OperationNode& var) const { - CGOpCode op = var.getOperationType(); - return isCondAssign(op) || - op == CGOpCode::ArrayCreation || - op == CGOpCode::SparseArrayCreation || - op == CGOpCode::AtomicForward || - op == CGOpCode::AtomicReverse || - op == CGOpCode::DependentMultiAssign || - op == CGOpCode::LoopStart || - op == CGOpCode::LoopEnd || - op == CGOpCode::IndexAssign || - op == CGOpCode::StartIf || - op == CGOpCode::ElseIf || - op == CGOpCode::Else || - op == CGOpCode::EndIf || - op == CGOpCode::CondResult || - op == CGOpCode::IndexDeclaration; - } - - virtual bool requiresVariableArgument(enum CGOpCode op, size_t argIndex) const override { - return op == CGOpCode::CondResult; - } - - inline const std::string& createVariableName(OperationNode& var) { - CGOpCode op = var.getOperationType(); - CPPADCG_ASSERT_UNKNOWN(getVariableID(var) > 0); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::AtomicForward); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::AtomicReverse); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::LoopStart); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::LoopEnd); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::Index); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::IndexAssign); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::IndexDeclaration); - - if (var.getName() == nullptr) { - if (op == CGOpCode::ArrayCreation) { - var.setName(_nameGen->generateTemporaryArray(var, getVariableID(var))); - - } else if (op == CGOpCode::SparseArrayCreation) { - var.setName(_nameGen->generateTemporarySparseArray(var, getVariableID(var))); - - } else if (op == CGOpCode::LoopIndexedDep) { - size_t pos = var.getInfo()[0]; - const IndexPattern* ip = _info->loopDependentIndexPatterns[pos]; - var.setName(_nameGen->generateIndexedDependent(var, getVariableID(var), *ip)); - - } else if (op == CGOpCode::LoopIndexedIndep) { - size_t pos = var.getInfo()[1]; - const IndexPattern* ip = _info->loopIndependentIndexPatterns[pos]; - var.setName(_nameGen->generateIndexedIndependent(var, getVariableID(var), *ip)); - - } else if (getVariableID(var) <= _independentSize) { - // independent variable - var.setName(_nameGen->generateIndependent(var, getVariableID(var))); - - } else if (getVariableID(var) < _minTemporaryVarID) { - // dependent variable - std::map::const_iterator it = _dependentIDs.find(getVariableID(var)); - CPPADCG_ASSERT_UNKNOWN(it != _dependentIDs.end()); - - size_t index = it->second; - var.setName(_nameGen->generateDependent(index)); - - } else if (op == CGOpCode::LoopIndexedTmp || op == CGOpCode::Tmp) { - CPPADCG_ASSERT_KNOWN(var.getArguments().size() >= 1, "Invalid number of arguments for loop indexed temporary operation"); - OperationNode* tmpVar = var.getArguments()[0].getOperation(); - CPPADCG_ASSERT_KNOWN(tmpVar != nullptr && tmpVar->getOperationType() == CGOpCode::TmpDcl, "Invalid arguments for loop indexed temporary operation"); - return createVariableName(*tmpVar); - - } else { - // temporary variable - var.setName(_nameGen->generateTemporary(var, getVariableID(var))); - } - } - - return *var.getName(); - } - - virtual bool requiresVariableDependencies() const override { - return false; - } - - virtual std::string print(const Argument& arg) { - if (arg.getOperation() != nullptr) { - // expression - return printExpression(*arg.getOperation()); - } else { - // parameter - return printParameter(*arg.getParameter()); - } - } - - virtual std::string printExpression(OperationNode& node) { - if (getVariableID(node) == 0) { - // print expression code - return printExpressionNoVarCheck(node); - } else { - return makeNodeName(node); - } - } - - virtual std::string printParameter(const Base& value) { - if(!_combineParameterNodes) { - std::string name = makeNodeName(value); - - _code << name; - _code << " [label=\""; - _code << std::setprecision(_parameterPrecision) << value; - _code << "\"]" << _endline; - - return name; - } else { - return makeNodeName(value); - } - } - - inline virtual std::string makeNodeName(const OperationNode& node) { - return "v" + std::to_string(node.getHandlerPosition()); - } - - inline std::string makeNodeName(const Argument& arg) { - if (arg.getOperation() != nullptr) { - // expression - return makeNodeName(*arg.getOperation()); - } else { - // parameter - return makeNodeName(*arg.getParameter()); - } - } - - inline virtual std::string makeNodeName(const Base& value) { - if(_combineParameterNodes) { - // node name for parameters which have the same node for the same value - _ss.str(""); - _ss << "\"" << std::setprecision(_parameterPrecision) << value << "\""; - return _ss.str(); - } else { - std::string name = "p" + std::to_string(parIdx_); - parIdx_++; - return name; - } - } - - inline std::string printNodeDeclaration(const OperationNode& op, - const std::ostringstream& label, - const std::string& shape = "") { - return printNodeDeclaration(op, label.str(), shape); - } - - virtual std::string printNodeDeclaration(const OperationNode& op, - const std::string& label = "", - const std::string& shape = "") { - std::string name = makeNodeName(op); - - _code << name << " [label=\""; - if(!label.empty()) { - _code << label; - } else { - _code << op.getOperationType(); - } - _code << "\""; - if (!shape.empty()) { - _code << ", shape=" << shape; - } - _code << "]" << _endline; - - return name; - } - - inline void printEdges(const std::string& name, - const OperationNode& node, - const std::string& style = "") { - const auto& args = node.getArguments(); - - std::vector aNames(args.size()); - for (size_t i = 0; i < args.size(); ++i) { - aNames[i] = print(args[i]); - } - - for (size_t i = 0; i < args.size(); ++i) { - if (i > 0) - _code << " "; - printEdge(aNames[i], name, style); - } - _code << _endline; - } - - inline void printEdges(const std::string& name, - const OperationNode& node, - const std::vector& args, - const std::string& style = "") { - size_t na = node.getArguments().size(); - size_t nna = args.size(); - CPPADCG_ASSERT_UNKNOWN(na >= nna); - - for (size_t i = 0; i < na; ++i) { - if (i > 0) - _code << " "; - if(i < nna && !args[i].empty()) { - printEdge(args[i], name, style); - } else { - std::string n = print(node.getArguments()[i]); - printEdge(n, name, style); - } - } - _code << _endline; - } - - inline void printEdges(const std::string& name, - const OperationNode& node, - const std::vector& args, - const std::vector& styles) { - size_t na = node.getArguments().size(); - size_t nna = args.size(); - size_t ns = styles.size(); - CPPADCG_ASSERT_UNKNOWN(na >= nna); - CPPADCG_ASSERT_UNKNOWN(na >= ns); - - std::string style; - for (size_t i = 0; i < args.size(); ++i) { - if (i > 0) - _code << " "; - - style = i < ns ? styles[i] : ""; - if(i < nna && !args[i].empty()) { - printEdge(args[i], name, style); - } else { - std::string n = print(node.getArguments()[i]); - printEdge(n, name, style); - } - } - _code << _endline; - } - - inline void printEdge(const OperationNode& from, - const std::string& to, - const std::string& style = "") { - _code << makeNodeName(from); - _code << " -> " << to; - if (!style.empty()) - _code << "[" << style << "]"; - } - - inline void printEdge(const std::string& from, - const std::string& to, - const std::string& style = "") { - _code << from << " -> " << to; - if (!style.empty()) - _code << "[" << style << "]"; - } - - virtual std::string printExpressionNoVarCheck(OperationNode& node) { - CGOpCode op = node.getOperationType(); - switch (op) { - case CGOpCode::ArrayCreation: - return printArrayCreationOp(node); - case CGOpCode::SparseArrayCreation: - return printSparseArrayCreationOp(node); - case CGOpCode::ArrayElement: - return printArrayElementOp(node); - case CGOpCode::Assign: - return printAssignOp(node); - - case CGOpCode::Abs: - case CGOpCode::Acos: - case CGOpCode::Asin: - case CGOpCode::Atan: - case CGOpCode::Cosh: - case CGOpCode::Cos: - case CGOpCode::Exp: - case CGOpCode::Log: - case CGOpCode::Sign: - case CGOpCode::Sinh: - case CGOpCode::Sin: - case CGOpCode::Sqrt: - case CGOpCode::Tanh: - case CGOpCode::Tan: - return printUnaryFunction(node); - case CGOpCode::AtomicForward: // atomicFunction.forward(q, p, vx, vy, tx, ty) - return printAtomicForwardOp(node); - case CGOpCode::AtomicReverse: // atomicFunction.reverse(p, tx, ty, px, py) - return printAtomicReverseOp(node); - case CGOpCode::Add: - return printOperationAdd(node); - case CGOpCode::Alias: - return printOperationAlias(node); - case CGOpCode::ComLt: - case CGOpCode::ComLe: - case CGOpCode::ComEq: - case CGOpCode::ComGe: - case CGOpCode::ComGt: - case CGOpCode::ComNe: - return printConditionalAssignment(node); - case CGOpCode::Div: - return printOperationDiv(node); - case CGOpCode::Inv: - // do nothing - return makeNodeName(node); - case CGOpCode::Mul: - return printOperationMul(node); - case CGOpCode::Pow: - return printPowFunction(node); - case CGOpCode::Pri: - // do nothing - return makeNodeName(node); - case CGOpCode::Sub: - return printOperationMinus(node); - - case CGOpCode::UnMinus: - return printOperationUnaryMinus(node); - - case CGOpCode::DependentMultiAssign: - return printDependentMultiAssign(node); - - case CGOpCode::Index: - return makeNodeName(node); // nothing to do - - case CGOpCode::IndexAssign: - return printIndexAssign(node); - case CGOpCode::IndexDeclaration: - return makeNodeName(node); // already done - - case CGOpCode::LoopStart: - return printLoopStart(node); - case CGOpCode::LoopIndexedIndep: - return printLoopIndexedIndep(node); - case CGOpCode::LoopIndexedDep: - return printLoopIndexedDep(node); - case CGOpCode::LoopIndexedTmp: - return printLoopIndexedTmp(node); - case CGOpCode::TmpDcl: - // nothing to do - return makeNodeName(node); - case CGOpCode::Tmp: - return printTmpVar(node); - case CGOpCode::LoopEnd: - return printLoopEnd(node); - case CGOpCode::IndexCondExpr: - return printIndexCondExprOp(node); - case CGOpCode::StartIf: - return printStartIf(node); - case CGOpCode::ElseIf: - return printElseIf(node); - case CGOpCode::Else: - return printElse(node); - case CGOpCode::EndIf: - return printEndIf(node); - case CGOpCode::CondResult: - return printCondResult(node); - default: - throw CGException("Unknown operation code '", op, "'."); - } - } - - virtual std::string printAssignOp(OperationNode& node) { - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 1, "Invalid number of arguments for assign operation"); - - return print(node.getArguments()[0]); - } - - virtual std::string printPowFunction(OperationNode& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for pow() function"); - - std::string a0 = print(op.getArguments()[0]); - std::string a1 = print(op.getArguments()[1]); - - std::string name = printNodeDeclaration(op); - - printEdges(name, op, std::vector{a0, a1}, std::vector{"label=\"$1\"", "label=\"$2\""}); - - return name; - } - - virtual std::string printUnaryFunction(OperationNode& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 1, "Invalid number of arguments for an unary function"); - - std::string a0 = print(op.getArguments()[0]); - - // TODO: improve this - _ss.str(""); - _ss << op.getOperationType(); - std::string label = _ss.str(); - auto it = label.find('('); - if (it != std::string::npos) { - label = label.substr(0, it); - } - std::string name = printNodeDeclaration(op, label); - - printEdges(name, op, std::vector {a0}); - - return name; - } - - virtual std::string printOperationAlias(OperationNode& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 1, "Invalid number of arguments for alias"); - - std::string a0 = print(op.getArguments()[0]); - - std::string name = printNodeDeclaration(op); - - printEdges(name, op, std::vector {a0}); - - return name; - } - - virtual std::string printOperationAdd(OperationNode& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for addition"); - - const Argument& left = op.getArguments()[0]; - const Argument& right = op.getArguments()[1]; - - std::string a0 = print(left); - std::string a1 = print(right); - - std::string name = printNodeDeclaration(op, "+"); - - printEdges(name, op, std::vector {a0, a1}); - - return name; - } - - virtual std::string printOperationMinus(OperationNode& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for subtraction"); - - const Argument& left = op.getArguments()[0]; - const Argument& right = op.getArguments()[1]; - - std::string a0 = print(left); - std::string a1 = print(right); - - std::string name = printNodeDeclaration(op); - - printEdges(name, op, std::vector {a0, a1}, std::vector{"label=\"$1\"", "label=\"$2\""}); - - return name; - } - - virtual std::string printOperationDiv(OperationNode& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for division"); - - const Argument& left = op.getArguments()[0]; - const Argument& right = op.getArguments()[1]; - - std::string a0 = print(left); - std::string a1 = print(right); - - std::string name = printNodeDeclaration(op); - - printEdges(name, op, std::vector {a0, a1}, std::vector{"label=\"$1\"", "label=\"$2\""}); - - return name; - } - - virtual std::string printOperationMul(OperationNode& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for multiplication"); - - const Argument& left = op.getArguments()[0]; - const Argument& right = op.getArguments()[1]; - - std::string a0 = print(left); - std::string a1 = print(right); - - std::string name = printNodeDeclaration(op, "×"); - - printEdges(name, op, std::vector {a0, a1}); - - return name; - } - - virtual std::string printOperationUnaryMinus(OperationNode& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 1, "Invalid number of arguments for unary minus"); - - const Argument& arg = op.getArguments()[0]; - - std::string a0 = print(arg); - - std::string name = printNodeDeclaration(op); - - printEdges(name, op, std::vector {a0}); - - return name; - } - - virtual std::string printConditionalAssignment(OperationNode& node) { - CPPADCG_ASSERT_UNKNOWN(getVariableID(node) > 0); - - const std::vector >& args = node.getArguments(); - const Argument& left = args[0]; - const Argument& right = args[1]; - const Argument& trueCase = args[2]; - const Argument& falseCase = args[3]; - - std::string a0 = print(left); - std::string a1 = print(right); - std::string a2 = print(trueCase); - std::string a3 = print(falseCase); - - std::string name = printNodeDeclaration(node, "", "diamond"); - - /** - * Connections - */ - printEdges(name, node, std::vector {a0, a1, a2, a3}, - std::vector{"label=\"left\"", "label=\"right\"", "label=\"true\"", "label=\"false\""}); - - return name; - } - - virtual std::string printArrayCreationOp(OperationNode& op); - - virtual std::string printSparseArrayCreationOp(OperationNode& op); - - inline size_t printArrayCreationUsingLoop(const std::string arrayName, - const OperationNode& array, - size_t startj, - const size_t* indexes); - - virtual std::string printArrayElementOp(OperationNode& op); - - virtual std::string printAtomicForwardOp(OperationNode& atomicFor) { - CPPADCG_ASSERT_KNOWN(atomicFor.getInfo().size() == 3, "Invalid number of information elements for atomic forward operation"); - int q = atomicFor.getInfo()[1]; - int p = atomicFor.getInfo()[2]; - size_t p1 = p + 1; - const std::vector >& opArgs = atomicFor.getArguments(); - CPPADCG_ASSERT_KNOWN(opArgs.size() == p1 * 2, "Invalid number of arguments for atomic forward operation"); - - size_t id = atomicFor.getInfo()[0]; - - std::string name = printNodeDeclaration(atomicFor, _info->atomicFunctionId2Name.at(id) + ".forward(" + std::to_string(q) + ", " + std::to_string(p) + ", tx, ty)"); - - /** - * Edges - */ - std::vector args(opArgs.size()); // argument node names - - std::vector*> tx(p1), ty(p1); - for (size_t k = 0; k < p1; k++) { - tx[k] = opArgs[0 * p1 + k].getOperation(); - ty[k] = opArgs[1 * p1 + k].getOperation(); - - args[0 * p1 + k] = print(*tx[k]); - args[1 * p1 + k] = print(*ty[k]); - } - - for (size_t k = 0; k < p1; k++) { - printEdge(args[0 * p1 + k], name, "label=\"tx" + std::to_string(k) + "\""); - _code << " "; - - printEdge(args[1 * p1 + k], name, "label=\"ty" + std::to_string(k) + "\""); - _code << " "; - } - _code << _endline; - - CPPADCG_ASSERT_KNOWN(tx[0]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - CPPADCG_ASSERT_KNOWN(p == 0 || tx[1]->getOperationType() == CGOpCode::SparseArrayCreation, "Invalid array type"); - CPPADCG_ASSERT_KNOWN(ty[p]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - - return name; - } - - virtual std::string printAtomicReverseOp(OperationNode& atomicRev) { - CPPADCG_ASSERT_KNOWN(atomicRev.getInfo().size() == 2, "Invalid number of information elements for atomic reverse operation"); - int p = atomicRev.getInfo()[1]; - size_t p1 = p + 1; - const std::vector >& opArgs = atomicRev.getArguments(); - CPPADCG_ASSERT_KNOWN(opArgs.size() == p1 * 4, "Invalid number of arguments for atomic reverse operation"); - - size_t id = atomicRev.getInfo()[0]; - - std::string name = printNodeDeclaration(atomicRev, _info->atomicFunctionId2Name.at(id) + ".reverse(" + std::to_string(p) + ", tx, px, py)"); - - /** - * Edges - */ - std::vector args(opArgs.size()); // argument node names - - std::vector*> tx(p1), px(p1), py(p1); - for (size_t k = 0; k < p1; k++) { - tx[k] = opArgs[0 * p1 + k].getOperation(); - px[k] = opArgs[2 * p1 + k].getOperation(); - py[k] = opArgs[3 * p1 + k].getOperation(); - - args[0 * p1 + k] = print(*tx[k]); - args[1 * p1 + k] = print(opArgs[1 * p1 + k]); // todo: consider not showing this - args[2 * p1 + k] = print(*px[k]); - args[3 * p1 + k] = print(*py[k]); - } - - for (size_t k = 0; k < p1; k++) { - printEdge(args[0 * p1 + k], name, "label=\"tx" + std::to_string(k) + "\""); - _code << " "; - - printEdge(args[1 * p1 + k], name, "label=\"ty" + std::to_string(k) + "\""); - _code << " "; - - printEdge(args[2 * p1 + k], name, "label=\"px" + std::to_string(k) + "\""); - _code << " "; - - printEdge(args[3 * p1 + k], name, "label=\"py" + std::to_string(k) + "\""); - _code << " "; - } - _code << _endline; - - CPPADCG_ASSERT_KNOWN(tx[0]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - CPPADCG_ASSERT_KNOWN(p == 0 || tx[1]->getOperationType() == CGOpCode::SparseArrayCreation, "Invalid array type"); - - CPPADCG_ASSERT_KNOWN(px[0]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - - CPPADCG_ASSERT_KNOWN(py[0]->getOperationType() == CGOpCode::SparseArrayCreation, "Invalid array type"); - CPPADCG_ASSERT_KNOWN(p == 0 || py[1]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - - return name; - } - - virtual std::string printDependentMultiAssign(OperationNode& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::DependentMultiAssign, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() > 0, "Invalid number of arguments"); - - std::string name = printNodeDeclaration(node, "+="); - - const std::vector >& args = node.getArguments(); - for (size_t a = 0; a < args.size(); a++) { - bool useArg = false; - const Argument& arg = args[a]; - std::string aName = print(arg); - - if (arg.getParameter() != nullptr) { - useArg = true; - } else { - CGOpCode op = arg.getOperation()->getOperationType(); - useArg = op != CGOpCode::DependentRefRhs && op != CGOpCode::LoopEnd && op != CGOpCode::EndIf; - } - - if (useArg) { - printEdge(aName, name, "label=\"+=\""); - _code << _endline; - break; - } else { - printEdge(aName, name, "color=grey"); - _code << _endline; - } - } - - return name; - } - - virtual std::string printLoopStart(OperationNode& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopStart, "Invalid node type"); - - LoopStartOperationNode& lnode = static_cast&> (node); - _currentLoops.push_back(&lnode); - - /** - * declaration - */ - const std::string& jj = *lnode.getIndex().getName(); - - _ss.str(""); - if (lnode.getIterationCountNode() != nullptr) { - _ss << "for " << jj << " ∈ [0, " << lnode.getIterationCountNode()->getIndex().getName() << "-1]"; - } else { - _ss << "for " << jj << " ∈ [0, " << (lnode.getIterationCount() - 1) << "]"; - } - std::string name = printNodeDeclaration(node, _ss, "parallelogram"); - - /** - * connections - */ - if (lnode.getIterationCountNode() != nullptr) { - // is label ready necessary? - printEdge(*lnode.getIterationCountNode(), name, "label=\"" + (*lnode.getIterationCountNode()->getIndex().getName()) + "\""); - _code << _endline; - } - - printEdge(lnode.getIndex(), name, "label=\"index " + jj + "\""); - _code << _endline; - - return name; - } - - virtual std::string printLoopEnd(OperationNode& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopEnd, "Invalid node type"); - - std::string name = printNodeDeclaration(node); - - printEdges(name, node, "color=grey"); - - _currentLoops.pop_back(); - - return name; - } - - virtual std::string printLoopIndexedDep(OperationNode& node) { - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 1, "Invalid number of arguments for loop indexed dependent operation"); - - std::string name = printNodeDeclaration(node); - - // LoopIndexedDep - printEdges(name, node); - - return name; - } - - virtual std::string printLoopIndexedIndep(OperationNode& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopIndexedIndep, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getInfo().size() == 1, "Invalid number of information elements for loop indexed independent operation"); - - size_t pos = node.getInfo()[1]; - const IndexPattern* ip = _info->loopIndependentIndexPatterns[pos]; - _ss << _nameGen->generateIndexedIndependent(node, getVariableID(node), *ip); - - std::string name = printNodeDeclaration(node, _ss); - - printEdges(name, node); - - return name; - } - - virtual std::string printLoopIndexedTmp(OperationNode& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopIndexedTmp, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 2, "Invalid number of arguments for loop indexed temporary operation"); - OperationNode* tmpVar = node.getArguments()[0].getOperation(); - CPPADCG_ASSERT_KNOWN(tmpVar != nullptr && tmpVar->getOperationType() == CGOpCode::TmpDcl, "Invalid arguments for loop indexed temporary operation"); - - std::string name = printNodeDeclaration(node); - - printEdges(name, node); - - return name; - } - - virtual std::string printTmpVar(OperationNode& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::Tmp, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() > 0, "Invalid number of arguments for temporary variable usage operation"); -#ifndef NDEBUG - OperationNode* tmpVar = node.getArguments()[0].getOperation(); - CPPADCG_ASSERT_KNOWN(tmpVar != nullptr && tmpVar->getOperationType() == CGOpCode::TmpDcl, "Invalid arguments for loop indexed temporary operation"); -#endif - // do nothing - - return makeNodeName(node); - } - - virtual std::string printIndexAssign(OperationNode& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::IndexAssign, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() > 0, "Invalid number of arguments for an index assignment operation"); - - IndexAssignOperationNode& inode = static_cast&> (node); - - const IndexPattern& ip = inode.getIndexPattern(); - _ss.str(""); - _ss << (*inode.getIndex().getName()) << " = "; - indexPattern2String(_ss, ip, inode.getIndexPatternIndexes()); - - std::string name = printNodeDeclaration(node, _ss); - - /** - * Connections - */ - for (const auto* idx: inode.getIndexPatternIndexes()) { - printEdge(*idx, name); - _code << " "; - } - _code << _endline; - - return name; - } - - virtual std::string printIndexCondExprOp(OperationNode& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::IndexCondExpr, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 1, "Invalid number of arguments for an index condition expression operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an index condition expression operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation()->getOperationType() == CGOpCode::Index, "Invalid argument for an index condition expression operation"); - - const std::vector& info = node.getInfo(); - - IndexOperationNode& iterationIndexOp = static_cast&> (*node.getArguments()[0].getOperation()); - const std::string& index = *iterationIndexOp.getIndex().getName(); - - _ss.str(""); - printIndexCondExpr(_ss, info, index); - - std::string name = printNodeDeclaration(node, _ss); - - return name; - } - - virtual std::string printStartIf(OperationNode& node) { - /** - * the first argument is the condition, following arguments are - * just extra dependencies that must be defined outside the if - */ - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::StartIf, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 1, "Invalid number of arguments for an 'if start' operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an 'if start' operation"); - - //printIndexCondExprOp(*node.getArguments()[0].getOperation()); - std::string name = printNodeDeclaration(node, "", "diamond"); - - printEdges(name, node, std::vector{}, - std::vector{"label=\"condition\""}); - - return name; - } - - virtual std::string printElseIf(OperationNode& node) { - /** - * the first argument is the condition, the second argument is the - * if start node, the following arguments are assignments in the - * previous if branch - */ - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::ElseIf, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 2, "Invalid number of arguments for an 'else if' operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an 'else if' operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[1].getOperation() != nullptr, "Invalid argument for an 'else if' operation"); - - std::string name = printNodeDeclaration(node, "", "diamond"); - - printEdges(name, node, std::vector{}, - std::vector{"label=\"false\"", "label=\"condition\""}); - - return name; - } - - virtual std::string printElse(OperationNode& node) { - /** - * the first argument is the if start node, the following arguments - * are assignments in the previous if branch - */ - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::Else, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 1, "Invalid number of arguments for an 'else' operation"); - - std::string name = printNodeDeclaration(node, "", "diamond"); - - printEdges(name, node, std::vector{}, - std::vector{"label=\"false\""}); - - return name; - } - - virtual std::string printEndIf(OperationNode& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::EndIf, "Invalid node type for an 'end if' operation"); - - std::string name = printNodeDeclaration(node, "", "diamond"); - - printEdges(name, node); - - return name; - } - - virtual std::string printCondResult(OperationNode& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::CondResult, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 2, "Invalid number of arguments for an assignment inside an if/else operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an an assignment inside an if/else operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[1].getOperation() != nullptr, "Invalid argument for an an assignment inside an if/else operation"); - - print(node.getArguments()[0]); // condition start (e.g if or else if) - print(node.getArguments()[1]); // temporary result - - std::string name = printNodeDeclaration(node, "", "diamond"); - - printEdges(name, node); - - return name; - } - - inline bool isDependent(const OperationNode& arg) const { - if (arg.getOperationType() == CGOpCode::LoopIndexedDep) { - return true; - } - size_t id = getVariableID(arg); - return id > _independentSize && id < _minTemporaryVarID; - } - - virtual void getComparison(std::ostream& os, enum CGOpCode op) const { - switch (op) { - case CGOpCode::ComLt: - os << "<"; - return; - - case CGOpCode::ComLe: - os << "≤"; - return; - - case CGOpCode::ComEq: - os << "=="; - return; - - case CGOpCode::ComGe: - os << "≥"; - return; - - case CGOpCode::ComGt: - os << ">"; - return; - - case CGOpCode::ComNe: - os << "≠"; - return; - - default: CPPAD_ASSERT_UNKNOWN(0); - } - throw CGException("Invalid comparison operator code"); // should never get here - } - - static bool isFunction(enum CGOpCode op) { - return isUnaryFunction(op) || op == CGOpCode::Pow; - } - - static bool isUnaryFunction(enum CGOpCode op) { - switch (op) { - case CGOpCode::Abs: - case CGOpCode::Acos: - case CGOpCode::Asin: - case CGOpCode::Atan: - case CGOpCode::Cosh: - case CGOpCode::Cos: - case CGOpCode::Exp: - case CGOpCode::Log: - case CGOpCode::Sign: - case CGOpCode::Sinh: - case CGOpCode::Sin: - case CGOpCode::Sqrt: - case CGOpCode::Tanh: - case CGOpCode::Tan: - return true; - default: - return false; - } - } - - static bool isCondAssign(enum CGOpCode op) { - switch (op) { - case CGOpCode::ComLt: - case CGOpCode::ComLe: - case CGOpCode::ComEq: - case CGOpCode::ComGe: - case CGOpCode::ComGt: - case CGOpCode::ComNe: - return true; - default: - return false; - } - } -}; - -template -const std::string LanguageDot::_C_STATIC_INDEX_ARRAY = "index"; - -template -const std::string LanguageDot::_C_SPARSE_INDEX_ARRAY = "idx"; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/dot/language_dot_arrays.hpp b/ct_core/include/ct/external/cppad/cg/lang/dot/language_dot_arrays.hpp deleted file mode 100644 index 80bbf7d12..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/dot/language_dot_arrays.hpp +++ /dev/null @@ -1,151 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_DOT_ARRAYS_INCLUDED -#define CPPAD_CG_LANGUAGE_DOT_ARRAYS_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -std::string LanguageDot::printArrayCreationOp(OperationNode& array) { - CPPADCG_ASSERT_KNOWN(array.getArguments().size() > 0, "Invalid number of arguments for array creation operation"); - const std::vector >& args = array.getArguments(); - const size_t argSize = args.size(); - - _ss.str(""); - _ss << "array[" << args.size() << "]"; - std::string name = printNodeDeclaration(array, _ss); - - for (size_t i = 0; i < argSize; i++) { - // try to use a loop for element assignment - size_t newI = printArrayCreationUsingLoop(name, array, i, nullptr); - - // print elements not assign in a loop - if (newI == i) { - // individual element assignment - std::string aName = print(args[i]); - - printEdge(aName, name, std::to_string(i)); // std::to_string(i) - _code << _endline; - - } else { - i = newI - 1; - } - } - - return name; -} - -template -std::string LanguageDot::printSparseArrayCreationOp(OperationNode& array) { - - const std::vector& info = array.getInfo(); - CPPADCG_ASSERT_KNOWN(info.size() > 0, "Invalid number of information elements for sparse array creation operation"); - - const std::vector >& args = array.getArguments(); - const size_t argSize = args.size(); - - CPPADCG_ASSERT_KNOWN(info.size() == argSize + 1, "Invalid number of arguments for sparse array creation operation"); - - _ss.str(""); - _ss << "sparse[" << info[0] << "]"; // nnz: args.size() - std::string name = printNodeDeclaration(array, _ss); - - if (argSize == 0) - return name; // empty array - - for (size_t i = 0; i < argSize; i++) { - // try to use a loop for element assignment - size_t newI = printArrayCreationUsingLoop(name, array, i, &info[i]); - - // print element values not assign in a loop - if (newI == i) { - // individual element assignment - std::string aName = print(args[i]); - - printEdge(aName, name, std::to_string(info[i + 1])); // std::to_string(i) - _code << _endline; - - } else { - i = newI - 1; - } - } - - return name; -} - -template -inline size_t LanguageDot::printArrayCreationUsingLoop(const std::string arrayName, - const OperationNode& array, - size_t starti, - const size_t* indexes) { - - const std::vector >& args = array.getArguments(); - const size_t argSize = args.size(); - size_t i = starti + 1; - - /** - * constant value? - */ - if(args[starti].getParameter() == nullptr) - return starti; - - const Base& value = *args[starti].getParameter(); - for (; i < argSize; i++) { - if (args[i].getParameter() == nullptr || - *args[i].getParameter() != value) { - break; // not the same constant value - } - - if (indexes != nullptr && i - starti != indexes[i] - indexes[starti]) - break; // not the same constant value - } - - if (i - starti < 3) - return starti; - - std::string aName = print(args[starti]); - - /** - * print the loop - */ - if (indexes != nullptr) - printEdge(aName, arrayName, std::to_string(indexes[starti]) + "..." + std::to_string(indexes[i])); - else - printEdge(aName, arrayName, std::to_string(starti) + "..." + std::to_string(i)); - _code << _endline; - - return i; -} - -template -std::string LanguageDot::printArrayElementOp(OperationNode& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for array element operation"); - CPPADCG_ASSERT_KNOWN(op.getArguments()[0].getOperation() != nullptr, "Invalid argument for array element operation"); - CPPADCG_ASSERT_KNOWN(op.getInfo().size() == 1, "Invalid number of information indexes for array element operation"); - - std::string name = makeNodeName(op); - - _ss.str(""); - _ss << "[" << op.getInfo()[0] << "]"; - printEdges(name, op, std::vector{}, std::vector{_ss.str()}); - - return name; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/dot/language_dot_index_patterns.hpp b/ct_core/include/ct/external/cppad/cg/lang/dot/language_dot_index_patterns.hpp deleted file mode 100644 index 07a3010ef..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/dot/language_dot_index_patterns.hpp +++ /dev/null @@ -1,262 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_DOT_INDEX_PATTERNS_INCLUDED -#define CPPAD_CG_LANGUAGE_DOT_INDEX_PATTERNS_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -inline void LanguageDot::generateNames4RandomIndexPatterns(const std::set& randomPatterns) { - std::ostringstream os; - - std::set usedNames; - - // save existing names so that they are not to overridden - // (independent variable names might have already used them) - for (RandomIndexPattern* ip : randomPatterns) { - if (!ip->getName().empty()) { - usedNames.insert(ip->getName()); - } - } - - // create new names for the index pattern arrays without a name - size_t c = 0; - for (RandomIndexPattern* ip : randomPatterns) { - if (ip->getName().empty()) { - // new name required - std::string name; - do { - os << _C_STATIC_INDEX_ARRAY << c; - name = os.str(); - os.str(""); - c++; - } while (usedNames.find(name) != usedNames.end()); - - ip->setName(name); - } - } - -} - -template -inline void LanguageDot::printRandomIndexPatternDeclaration(std::ostringstream& os, - const std::set& randomPatterns) { - if (randomPatterns.empty()) - return; - - _code << "subgraph index {" << _endline; - _code << " rank=same" << _endline; - for (RandomIndexPattern* ip : randomPatterns) { - os << "idx_" << ip->getName() << "[label=\""; - if (ip->getType() == IndexPatternType::Random1D) { - /** - * 1D - */ - Random1DIndexPattern* ip1 = static_cast (ip); - const std::map& x2y = ip1->getValues(); - - std::vector y(x2y.rbegin()->first + 1); - for (const std::pair& p : x2y) - y[p.first] = p.second; - - printStaticIndexArray(os, ip->getName(), y); - } else { - CPPADCG_ASSERT_UNKNOWN(ip->getType() == IndexPatternType::Random2D); - /** - * 2D - */ - Random2DIndexPattern* ip2 = static_cast (ip); - printStaticIndexMatrix(os, ip->getName(), ip2->getValues()); - } - - os << "\"]"; - os << _endline; - } - _code << "}" << _endline; -} - -template -void LanguageDot::printStaticIndexArray(std::ostringstream& os, - const std::string& name, - const std::vector& values) { - os << name << " = ["; - for (size_t i = 0; i < values.size(); i++) { - if (i > 0) - os << ","; - os << values[i]; - } - os << "]"; -} - -template -void LanguageDot::printStaticIndexMatrix(std::ostringstream& os, - const std::string& name, - const std::map >& values) { - std::map >::const_iterator it; - std::map::const_iterator ity2z; - - os << name << "= ["; - for (it = values.begin(); it != values.end(); ++it) { - if (it != values.begin()) - os << it->first << ",\\n"; - os << it->first << ":["; - size_t y = 0; - for (ity2z = it->second.begin(); ity2z != it->second.end(); ++ity2z) { - if (ity2z->first != y) { - while (ity2z->first != y) { - if (y > 0) os << ", "; - os << "0"; - y++; - } - } - - if (y > 0) os << ", "; - os << ity2z->second; - - y++; - } - os << "]"; - } - os << "]"; -} - -template -inline void LanguageDot::indexPattern2String(std::ostream& os, - const IndexPattern& ip, - const OperationNode& index) { - indexPattern2String(os, ip,{&index}); -} - -template -inline void LanguageDot::indexPattern2String(std::ostream& os, - const IndexPattern& ip, - const std::vector*>& indexes) { - std::stringstream ss; - switch (ip.getType()) { - case IndexPatternType::Linear: // y = x * a + b - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 1, "Invalid number of indexes"); - const LinearIndexPattern& lip = static_cast (ip); - linearIndexPattern2String(os, lip, *indexes[0]); - return; - } - case IndexPatternType::Sectioned: - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 1, "Invalid number of indexes"); - const SectionedIndexPattern* lip = static_cast (&ip); - const std::map& sections = lip->getLinearSections(); - size_t sSize = sections.size(); - CPPADCG_ASSERT_UNKNOWN(sSize > 1); - - std::map::const_iterator its = sections.begin(); - for (size_t s = 0; s < sSize - 1; s++) { - const IndexPattern* lp = its->second; - ++its; - size_t xStart = its->first; - - os << (*indexes[0]->getName()) << " < " << xStart << ")? "; - indexPattern2String(os, *lp, *indexes[0]); - os << ": "; - } - indexPattern2String(os, *its->second, *indexes[0]); - - return; - } - - case IndexPatternType::Plane2D: // y = f(x) + f(z) - { - CPPADCG_ASSERT_KNOWN(indexes.size() >= 1, "Invalid number of indexes"); - const Plane2DIndexPattern& pip = static_cast (ip); - bool useParens = pip.getPattern1() != nullptr && pip.getPattern2() != nullptr; - - if (useParens) os << "("; - - if (pip.getPattern1() != nullptr) - indexPattern2String(os, *pip.getPattern1(), *indexes[0]); - - if (useParens) os << ") + ("; - - if (pip.getPattern2() != nullptr) - indexPattern2String(os, *pip.getPattern2(), *indexes.back()); - - if (useParens) os << ")"; - - return; - } - case IndexPatternType::Random1D: - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 1, "Invalid number of indexes"); - const Random1DIndexPattern& rip = static_cast (ip); - CPPADCG_ASSERT_KNOWN(!rip.getName().empty(), "Invalid name for array"); - os << rip.getName() << "[" << (*indexes[0]->getName()) << "]"; - return; - } - case IndexPatternType::Random2D: - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 2, "Invalid number of indexes"); - const Random2DIndexPattern& rip = static_cast (ip); - CPPADCG_ASSERT_KNOWN(!rip.getName().empty(), "Invalid name for array"); - os << rip.getName() << - "[" << (*indexes[0]->getName()) << "]" - "[" << (*indexes[1]->getName()) << "]"; - return; - } - default: - CPPADCG_ASSERT_UNKNOWN(false); // should never reach this - return; - } -} - -template -inline void LanguageDot::linearIndexPattern2String(std::ostream& os, - const LinearIndexPattern& lip, - const OperationNode& index) { - long dy = lip.getLinearSlopeDy(); - long dx = lip.getLinearSlopeDx(); - long b = lip.getLinearConstantTerm(); - long xOffset = lip.getXOffset(); - - if (dy != 0) { - if (xOffset != 0) { - os << "("; - } - os << (*index.getName()); - if (xOffset != 0) { - os << " -" << xOffset << ")"; - } - - if (dx != 1) { - os << "/" << dx; - } - if (dy != 1) { - os << "×" << dy; - } - } else if (b == 0) { - os << "0"; // when dy == 0 and b == 0 - } - - if (b != 0) { - if (dy != 0) - os << "+"; - os << b; - } - -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/language.hpp b/ct_core/include/ct/external/cppad/cg/lang/language.hpp deleted file mode 100644 index 4c5e16b0e..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/language.hpp +++ /dev/null @@ -1,190 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_INCLUDED -#define CPPAD_CG_LANGUAGE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Information required for the generation of source code for a language - * - * @author Joao Leal - */ -template -class LanguageGenerationData { -public: - typedef OperationNode Node; - typedef typename CodeHandler::ScopeIDType ScopeIDType; -public: - /** - * The independent variables - */ - const std::vector& independent; - /** - * The dependent variables - */ - const ArrayWrapper >& dependent; - /** - * The lowest ID used for temporary variables - */ - size_t minTemporaryVarID; - /** - * Provides the variable ID that was altered/assigned to operation nodes. - * Zero means that no variable is assigned. - */ - const CodeHandlerVector& varId; - /** - * Variable assignment order in the source code - */ - const std::vector& variableOrder; - /** - * maps dependencies between variables in variableOrder - */ - const std::vector>& variableDependencies; - /** - * Provides the rules for variable name creation - */ - VariableNameGenerator& nameGen; - /** - * maps atomic function IDs to their internal index - */ - const std::map& atomicFunctionId2Index; - /** - * maps atomic function IDs to their names - */ - const std::map& atomicFunctionId2Name; - /** - * the maximum forward mode order each atomic function is called - * (-1 means forward mode not used) - */ - const std::vector& atomicFunctionsMaxForward; - /** - * the maximum reverse mode order each atomic function is called - * (-1 means reverse mode not used) - */ - const std::vector& atomicFunctionsMaxReverse; - /** - * a flag indicating whether or not temporary variable IDs have been recycled - */ - const bool reuseIDs; - // - const std::set& indexes; - // - const std::set& indexRandomPatterns; - // - const std::vector& loopDependentIndexPatterns; - // - const std::vector& loopIndependentIndexPatterns; - /** - * the total number of times the result of an operation node is used - */ - const CodeHandlerVector& totalUseCount; - /** - * scope of each managed operation node - */ - const CodeHandlerVector& scope; - /** - * Auxiliary index (might not be used) - */ - IndexOperationNode& auxIterationIndexOp; - /** - * whether or not the dependent variables should be zeroed before - * executing the operation graph - */ - const bool zeroDependents; -public: - - LanguageGenerationData(const std::vector& ind, - const ArrayWrapper >& dep, - size_t minTempVID, - const CodeHandlerVector& varIds, - const std::vector& vo, - const std::vector>& variableDependencies, - VariableNameGenerator& ng, - const std::map& atomicId2Index, - const std::map& atomicId2Name, - const std::vector& atomicMaxForward, - const std::vector& atomicMaxReverse, - const bool ri, - const std::set& indexes, - const std::set& idxRandomPatterns, - const std::vector& dependentIndexPatterns, - const std::vector& independentIndexPatterns, - const CodeHandlerVector& totalUseCount, - const CodeHandlerVector& scope, - IndexOperationNode& auxIterationIndexOp, - bool zero) : - independent(ind), - dependent(dep), - minTemporaryVarID(minTempVID), - varId(varIds), - variableOrder(vo), - variableDependencies(variableDependencies), - nameGen(ng), - atomicFunctionId2Index(atomicId2Index), - atomicFunctionId2Name(atomicId2Name), - atomicFunctionsMaxForward(atomicMaxForward), - atomicFunctionsMaxReverse(atomicMaxReverse), - reuseIDs(ri), - indexes(indexes), - indexRandomPatterns(idxRandomPatterns), - loopDependentIndexPatterns(dependentIndexPatterns), - loopIndependentIndexPatterns(independentIndexPatterns), - totalUseCount(totalUseCount), - scope(scope), - auxIterationIndexOp(auxIterationIndexOp), - zeroDependents(zero) { - } -}; - -/** - * Creates the source code for a specific language - * - * @author Joao Leal - */ -template -class Language { - friend class CodeHandler; -public: - typedef OperationNode Node; -protected: - virtual void generateSourceCode(std::ostream& out, - const std::unique_ptr >& info) = 0; - - /** - * Whether or not a new variable is created as a result of this operation - * - * @param op Operation - * @return true if a new variable is created - */ - virtual bool createsNewVariable(const Node& op, - size_t totalUseCount) const = 0; - - virtual bool requiresVariableArgument(enum CGOpCode op, - size_t argIndex) const = 0; - - /** - * Whether or not this language can use information regarding the - * dependencies between different equations/variables. - */ - virtual bool requiresVariableDependencies() const = 0; - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/latex/lang_latex_custom_var_name_gen.hpp b/ct_core/include/ct/external/cppad/cg/lang/latex/lang_latex_custom_var_name_gen.hpp deleted file mode 100644 index 23c303ab6..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/latex/lang_latex_custom_var_name_gen.hpp +++ /dev/null @@ -1,101 +0,0 @@ -#ifndef CPPAD_CG_LANG_LATEX_CUSTOM_VAR_NAME_GEN_INCLUDED -#define CPPAD_CG_LANG_LATEX_CUSTOM_VAR_NAME_GEN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Creates variables names for the source code using a list of provided - * custom names. - * - * @author Joao Leal - */ -template -class LangLatexCustomVariableNameGenerator : public LangLatexDefaultVariableNameGenerator { -protected: - typedef LangLatexDefaultVariableNameGenerator Super; - // the custom names for the dependent variables - const std::vector depNames_; - // the custom names for the independent variables - const std::vector indepNames_; -public: - - LangLatexCustomVariableNameGenerator(const std::vector& depNames, - const std::vector& indepNames, - const std::string& depName = "y", - const std::string& indepName = "x", - const std::string& tmpName = "v", - const std::string& tmpArrayName = "\\mathbf{a}", - const std::string& tmpSparseArrayName = "\\mathbf{s}") : - LangLatexDefaultVariableNameGenerator(depName, indepName, tmpName, tmpArrayName, tmpSparseArrayName), - depNames_(depNames), - indepNames_(indepNames) { - } - - virtual std::string generateDependent(size_t index) override { - if (index < depNames_.size() && !depNames_[index].empty()) { - return depNames_[index]; - } else { - return Super::generateDependent(index); - } - } - - virtual std::string generateIndependent(const OperationNode& independent, - size_t id) override { - size_t index = id - 1; - if (index < indepNames_.size() && !indepNames_[index].empty()) { - return indepNames_[index]; - } else { - return Super::generateIndependent(independent, id); - } - } - - virtual bool isConsecutiveInIndepArray(const OperationNode& indepFirst, - size_t idFirst, - const OperationNode& indepSecond, - size_t idSecond) override { - size_t index1 = idFirst - 1; - size_t index2 = idSecond - 1; - - if ((index1 > indepNames_.size() || indepNames_[index1].empty()) && - (index2 > indepNames_.size() || indepNames_[index2].empty())) { - return index1 + 1 == index2; - } else { - return false; // individual names used (not elements of arrays) - } - } - - virtual bool isInSameIndependentArray(const OperationNode& indep1, - size_t id1, - const OperationNode& indep2, - size_t id2) override { - size_t index1 = id1 - 1; - size_t index2 = id2 - 1; - - return (index1 > indepNames_.size() || indepNames_[index1].empty()) && - (index2 > indepNames_.size() || indepNames_[index2].empty()); - } - - inline virtual ~LangLatexCustomVariableNameGenerator() { - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/latex/lang_latex_default_var_name_gen.hpp b/ct_core/include/ct/external/cppad/cg/lang/latex/lang_latex_default_var_name_gen.hpp deleted file mode 100644 index da668c2d9..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/latex/lang_latex_default_var_name_gen.hpp +++ /dev/null @@ -1,287 +0,0 @@ -#ifndef CPPAD_CG_LANG_LATEX_DEFAULT_VAR_NAME_GEN_INCLUDED -#define CPPAD_CG_LANG_LATEX_DEFAULT_VAR_NAME_GEN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Creates variables names for the source code. - * - * @author Joao Leal - */ -template -class LangLatexDefaultVariableNameGenerator : public VariableNameGenerator { -protected: - // auxiliary string stream - std::stringstream _ss; - // array name of the dependent variables - std::string _depName; - // array name of the independent variables - std::string _indepName; - // array name of the temporary variables - std::string _tmpName; - // array name of the temporary array variables - std::string _tmpArrayName; - // sparse array name of the temporary array variables - std::string _tmpSparseArrayName; - // the lowest variable ID used for the temporary variables - size_t _minTemporaryID; - // the highest variable ID used for the temporary variables - size_t _maxTemporaryID; - // the highest ID used for the temporary array variables - size_t _maxTemporaryArrayID; - // the highest ID used for the temporary sparse array variables - size_t _maxTemporarySparseArrayID; -public: - - inline LangLatexDefaultVariableNameGenerator(const std::string& depName = "y", - const std::string& indepName = "x", - const std::string& tmpName = "v", - const std::string& tmpArrayName = "\\mathbf{a}", - const std::string& tmpSparseArrayName = "\\mathbf{s}") : - _depName(depName), - _indepName(indepName), - _tmpName(tmpName), - _tmpArrayName(tmpArrayName), - _tmpSparseArrayName(tmpSparseArrayName), - _minTemporaryID(0), // not really required (but it avoids warnings) - _maxTemporaryID(0), // not really required (but it avoids warnings) - _maxTemporaryArrayID(0), // not really required (but it avoids warnings) - _maxTemporarySparseArrayID(0) { // not really required (but it avoids warnings) - - this->_independent.push_back(FuncArgument(_indepName)); - this->_dependent.push_back(FuncArgument(_depName)); - this->_temporary.push_back(FuncArgument(_tmpName)); - this->_temporary.push_back(FuncArgument(_tmpArrayName)); - this->_temporary.push_back(FuncArgument(_tmpSparseArrayName)); - } - - inline virtual size_t getMinTemporaryVariableID() const override { - return _minTemporaryID; - } - - inline virtual size_t getMaxTemporaryVariableID() const override { - return _maxTemporaryID; - } - - inline virtual size_t getMaxTemporaryArrayVariableID() const override { - return _maxTemporaryArrayID; - } - - virtual size_t getMaxTemporarySparseArrayVariableID() const override { - return _maxTemporarySparseArrayID; - } - - inline virtual std::string generateDependent(size_t index) override { - _ss.clear(); - _ss.str(""); - - _ss << _depName; - latexIndex(_ss, index); - - return _ss.str(); - } - - inline virtual std::string generateIndependent(const OperationNode& independent, - size_t id) override { - _ss.clear(); - _ss.str(""); - - _ss << _indepName; - latexIndex(_ss, id - 1); - - return _ss.str(); - } - - inline virtual std::string generateTemporary(const OperationNode& variable, - size_t id) override { - _ss.clear(); - _ss.str(""); - - if (this->_temporary[0].array) { - _ss << _tmpName; - latexIndex(_ss, id - this->_minTemporaryID); - } else { - _ss << _tmpName << id; - latexIndex(_ss, id); - } - - return _ss.str(); - } - - virtual std::string generateTemporaryArray(const OperationNode& variable, - size_t id) override { - _ss.clear(); - _ss.str(""); - - CPPADCG_ASSERT_UNKNOWN(variable.getOperationType() == CGOpCode::ArrayCreation); - - _ss << "\\&" << _tmpArrayName; ///////////////////////////////////////// - latexIndex(_ss, id - 1); - - return _ss.str(); - } - - virtual std::string generateTemporarySparseArray(const OperationNode& variable, - size_t id) override { - _ss.clear(); - _ss.str(""); - - CPPADCG_ASSERT_UNKNOWN(variable.getOperationType() == CGOpCode::SparseArrayCreation); - - _ss << "\\&" << _tmpSparseArrayName; ///////////////////////////////////////// - latexIndex(_ss, id - 1); - - return _ss.str(); - } - - virtual std::string generateIndexedDependent(const OperationNode& var, - size_t id, - const IndexPattern& ip) override { - CPPADCG_ASSERT_KNOWN(var.getOperationType() == CGOpCode::LoopIndexedDep, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(!var.getArguments().empty(), "Invalid number of arguments"); - - _ss.clear(); - _ss.str(""); - - std::string index = LanguageC::indexPattern2String(ip, getIndexes(var, 1)); - _ss << _depName << "_"; - if (index.size() > 1) - _ss << "{" << index << "}"; - else - _ss << index; - - return _ss.str(); - } - - virtual std::string generateIndexedIndependent(const OperationNode& independent, - size_t id, - const IndexPattern& ip) override { - CPPADCG_ASSERT_KNOWN(independent.getOperationType() == CGOpCode::LoopIndexedIndep, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(independent.getArguments().size() > 0, "Invalid number of arguments"); - - _ss.clear(); - _ss.str(""); - - std::string index = LanguageC::indexPattern2String(ip, getIndexes(independent)); - _ss << _indepName << "_"; - if (index.size() > 1) - _ss << "{" << index << "}"; - else - _ss << index; - - return _ss.str(); - } - - inline virtual void setTemporaryVariableID(size_t minTempID, - size_t maxTempID, - size_t maxTempArrayID, - size_t maxTempSparseArrayID) override { - _minTemporaryID = minTempID; - _maxTemporaryID = maxTempID; - _maxTemporaryArrayID = maxTempArrayID; - _maxTemporarySparseArrayID = maxTempSparseArrayID; - - // if - // _minTemporaryID == _maxTemporaryID + 1 - // then no temporary variables are being used - CPPADCG_ASSERT_UNKNOWN(_minTemporaryID <= _maxTemporaryID + 1); - } - - virtual const std::string& getIndependentArrayName(const OperationNode& indep, - size_t id) override { - return _indepName; - } - - virtual size_t getIndependentArrayIndex(const OperationNode& indep, - size_t id) override { - return id - 1; - } - - virtual bool isConsecutiveInIndepArray(const OperationNode& indepFirst, - size_t idFirst, - const OperationNode& indepSecond, - size_t idSecond) override { - return idFirst + 1 == idSecond; - } - - virtual bool isInSameIndependentArray(const OperationNode& indep1, - size_t id1, - const OperationNode& indep2, - size_t id2) override { - return true; - } - - virtual const std::string& getTemporaryVarArrayName(const OperationNode& var, - size_t id) override { - return _tmpName; - } - - virtual size_t getTemporaryVarArrayIndex(const OperationNode& var, - size_t id) override { - return id - this->_minTemporaryID; - } - - virtual bool isConsecutiveInTemporaryVarArray(const OperationNode& varFirst, - size_t idFirst, - const OperationNode& varSecond, - size_t idSecond) override { - return idFirst + 1 == idSecond; - } - - virtual bool isInSameTemporaryVarArray(const OperationNode& var1, - size_t id1, - const OperationNode& var2, - size_t id2) override { - return true; - } - - inline virtual ~LangLatexDefaultVariableNameGenerator() { - } -protected: - - static inline std::stringstream& latexIndex(std::stringstream& ss, - size_t index) { - ss << "_"; - if (index < 10) - ss << index; - else - ss << "{" << index << "}"; - - return ss; - } - - static inline std::vector*> getIndexes(const OperationNode& var, - size_t offset = 0) { - const std::vector >& args = var.getArguments(); - std::vector*> indexes(args.size() - offset); - - for (size_t a = offset; a < args.size(); a++) { - CPPADCG_ASSERT_KNOWN(args[a].getOperation() != nullptr, "Invalid argument"); - CPPADCG_ASSERT_KNOWN(args[a].getOperation()->getOperationType() == CGOpCode::Index, "Invalid argument"); - - indexes[a - offset] = &static_cast*> (args[a].getOperation())->getIndex(); - } - - return indexes; - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/latex/language_latex.hpp b/ct_core/include/ct/external/cppad/cg/lang/latex/language_latex.hpp deleted file mode 100644 index a0e8d1907..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/latex/language_latex.hpp +++ /dev/null @@ -1,2164 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_LATEX_INCLUDED -#define CPPAD_CG_LANGUAGE_LATEX_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Generates code for the Latex language. - * It creates a generic implementation using custom latex environments which - * must be implemented by the user. - * - * @author Joao Leal - */ -template -class LanguageLatex : public Language { -public: - typedef OperationNode Node; - typedef Argument Arg; -protected: - static const std::string _C_STATIC_INDEX_ARRAY; - static const std::string _C_SPARSE_INDEX_ARRAY; - static const std::string _COMP_OP_LT; - static const std::string _COMP_OP_LE; - static const std::string _COMP_OP_EQ; - static const std::string _COMP_OP_GE; - static const std::string _COMP_OP_GT; - static const std::string _COMP_OP_NE; - static const std::string _ATOMIC_TX; - static const std::string _ATOMIC_TY; - static const std::string _ATOMIC_PX; - static const std::string _ATOMIC_PY; -protected: - // information from the code handler (not owned) - LanguageGenerationData* _info; - // current indentation - size_t _indentationLevel; - // text before a variable name - std::string _startVar; - // text after a variable name - std::string _endVar; - // text before a dependent variable name - std::string _startDepVar; - // text after a dependent variable name - std::string _endDepVar; - // text before an independent variable name - std::string _startIndepVar; - // text after an independent variable name - std::string _endIndepVar; - // text before an individual equation - std::string _startEq; - // text after an individual equation - std::string _endEq; - // text before a line in the algorithm - std::string _startAlgLine; - // text after a line in the algorithm - std::string _endAlgLine; - // text before an equation block with multiple lines with the same indentation - std::string _startEqBlock; - // text after an equation block with multiple lines with the same indentation - std::string _endEqBlock; - std::string _algFileStart; - std::string _algFileEnd; - std::string _forStart; - std::string _forEnd; - std::string _conditionStart; - std::string _conditionEnd; - std::string _ifStart; - std::string _ifEnd; - std::string _elseIfStart; - std::string _elseIfEnd; - std::string _elseStart; - std::string _elseEnd; - std::string _assignStr; - // markup for multiplications - std::string _multOpStr; - // markup for multiplications with parameters - std::string _multValOpStr; - // new line characters - std::string _endline; - // output stream for the generated source code - std::ostringstream _code; - // creates the variable names - VariableNameGenerator* _nameGen; - // auxiliary string stream - std::ostringstream _ss; - // - size_t _independentSize; - // - size_t _minTemporaryVarID; - // maps the variable IDs to the their position in the dependent vector - // (some IDs may be the same as the independent variables when dep = indep) - std::map _dependentIDs; - // the dependent variable vector - const ArrayWrapper >* _dependent; - // the temporary variables that may require a declaration - std::map _temporary; - // whether or not to ignore assignment of constant zero values to dependent variables - bool _ignoreZeroDepAssign; - // the name of the file to be created without the extension - std::string _filename; - // the maximum number of assignment (~lines) per local file - size_t _maxAssignmentsPerFile; - // - std::map* _sources; - // the values in the temporary array - std::vector _tmpArrayValues; - // the values in the temporary sparse array - std::vector _tmpSparseArrayValues; - // - std::vector*> _currentLoops; - // the maximum precision used to print values - size_t _parameterPrecision; - // whether or not we are in an equation/align block - bool _inEquationEnv; - // whether or not to always enclose the base of a power within parenthesis - bool _powBaseEnclose; -private: - std::string auxArrayName_; - -public: - - /** - * Creates a Latex language source code generator - */ - LanguageLatex() : - _info(nullptr), - _indentationLevel(0), - _startVar("\\begin{CGVar}"), - _endVar("\\end{CGVar}"), - _startDepVar("\\begin{CGDepVar}"), - _endDepVar("\\end{CGDepVar}"), - _startIndepVar("\\begin{CGIndVar}"), - _endIndepVar("\\end{CGIndVar}"), - _startEq("\\begin{CGEq}"), - _endEq("\\end{CGEq}"), - _startAlgLine("\\begin{CGLine}"), - _endAlgLine("\\end{CGLine}"), - _startEqBlock("\\begin{CGEqBlock}"), - _endEqBlock("\\end{CGEqBlock}"), - _algFileStart("\\begin{CGAlgFile}"), - _algFileEnd("\\end{CGAlgFile}"), - _forStart("\\begin{CGFor}"), - _forEnd("\\end{CGFor}"), - _conditionStart("\\begin{CGCond}"), - _conditionEnd("\\end{CGCond}"), - _ifStart("\\begin{CGIf}"), - _ifEnd("\\end{CGIf}"), - _elseIfStart("\\begin{CGElseIf}"), - _elseIfEnd("\\end{CGElseIf}"), - _elseStart("\\begin{CGElse}"), - _elseEnd("\\end{CGElse}"), - _assignStr(" = "), - _multOpStr(" "), - _multValOpStr("\\times"), - _endline("\n"), - _nameGen(nullptr), - _independentSize(0), // not really required (but it avoids warnings) - _minTemporaryVarID(0), // not really required (but it avoids warnings) - _dependent(nullptr), - _ignoreZeroDepAssign(false), - _filename("algorithm"), - _maxAssignmentsPerFile(0), - _sources(nullptr), - _parameterPrecision(std::numeric_limits::digits10), - _inEquationEnv(false), - _powBaseEnclose(false) { - } - - inline const std::string& getAssignString() const { - return _assignStr; - } - - inline void setAssignString(const std::string& assign) { - _assignStr = assign; - } - - inline bool isIgnoreZeroDepAssign() const { - return _ignoreZeroDepAssign; - } - - inline void setIgnoreZeroDepAssign(bool ignore) { - _ignoreZeroDepAssign = ignore; - } - - virtual void setFilename(const std::string& name) { - _filename = name; - } - - /** - * Defines the Latex environment for each variable. - * - * @param begin a string creating the environment - * @param end a string terminating the environment - */ - virtual void setVariableEnvironment(const std::string& begin, - const std::string& end) { - _startVar = begin; - _endVar = end; - } - - /** - * Provides the string used to create the environment for each variable. - */ - virtual const std::string& getVariableEnvironmentStart() const { - return _startVar; - } - - /** - * Provides the string used to terminate the environment for each variable. - */ - virtual const std::string& getVariableEnvironmentEnd() const { - return _endVar; - } - - /** - * Defines the Latex environment for each dependent variable. - * - * @param begin a string creating the environment - * @param end a string terminating the environment - */ - virtual void setDependentVarEnvironment(const std::string& begin, - const std::string& end) { - _startDepVar = begin; - _endDepVar = end; - } - - /** - * Provides the string used to create the environment for each dependent variable. - */ - virtual const std::string& getDependentVarEnvironmentStart() const { - return _startDepVar; - } - - /** - * Provides the string used to terminate the environment for each dependent variable. - */ - virtual const std::string& getDependentVarEnvironmentEnd() const { - return _endDepVar; - } - - /** - * Defines the Latex environment for each independent variable. - * - * @param begin a string creating the environment - * @param end a string terminating the environment - */ - virtual void setIndependentVarEnvironment(const std::string& begin, - const std::string& end) { - _startIndepVar = begin; - _endIndepVar = end; - } - - /** - * Provides the string used to create the environment for each independent variable. - */ - virtual const std::string& getIndependentVarEnvironmentStart() const { - return _startIndepVar; - } - - /** - * Provides the string used to terminate the environment for each independent variable. - */ - virtual const std::string& getIndependentVarEnvironmentEnd() const { - return _endIndepVar; - } - - /** - * Defines the Latex environment for each equation. - * - * @param begin a string creating the environment (e.g. "$", "\\begin{algomathdisplay}", "\\[") - * @param end a string terminating the environment (e.g. "$\\;", "\\end{algomathdisplay}\\;", "\\]\\;") - */ - virtual void setEquationEnvironment(const std::string& begin, - const std::string& end) { - _startEq = begin; - _endEq = end; - } - - /** - * Provides the string used to create the environment for each equation. - */ - virtual const std::string& getEquationEnvironmentStart() const { - return _startEq; - } - - /** - * Provides the string used to terminate the environment for each equation. - */ - virtual const std::string& getEquationEnvironmentEnd() const { - return _endEq; - } - - /** - * Defines the Latex environment for each algorithm line. - * - * @param begin a string creating the environment - * @param end a string terminating the environment - */ - virtual void setAlgorithmLineEnvironment(const std::string& begin, - const std::string& end) { - _startAlgLine = begin; - _endAlgLine = end; - } - - /** - * Provides the string used to create the environment for each line. - */ - virtual const std::string& getAlgorithmLineEnvironmentStart() const { - return _startAlgLine; - } - - /** - * Provides the string used to terminate the environment for each line. - */ - virtual const std::string& getAlgorithmLineEnvironmentEnd() const { - return _endAlgLine; - } - - /** - * Defines the Latex environment for each equation block which can contain - * multiple equation lines with the same indentation. - * - * @param begin a string creating the environment - * @param end a string terminating the environment - */ - virtual void setEquationBlockEnvironment(const std::string& begin, - const std::string& end) { - _startEqBlock = begin; - _endEqBlock = end; - } - - /** - * Provides the string used to create the environment for each equation - * block which can contain multiple equation lines with the same indentation. - */ - virtual const std::string& getEquationBlockEnvironmentStart() const { - return _startEqBlock; - } - - /** - * Provides the string used to terminate the environment for each equation - * block which can contain multiple equation lines with the same indentation. - */ - virtual const std::string& getEquationBlockEnvironmentEnd() const { - return _endEqBlock; - } - - /** - * Defines the Latex environment for each algorithm file. - * - * @param begin a string creating the environment - * @param end a string terminating the environment - */ - virtual void setAgorithmFileEnvironment(const std::string& begin, - const std::string& end) { - _algFileStart = begin; - _algFileEnd = end; - } - - /** - * Provides the string used to create the environment for each algorithm file. - */ - virtual const std::string& getAgorithmFileEnvironmentStart() const { - return _algFileStart; - } - - /** - * Provides the string used to terminate the environment for each algorithm file. - */ - virtual const std::string& getAgorithmFileEnvironmentEnd() const { - return _algFileEnd; - } - - /** - * Defines the Latex environment for each for loop. - * - * @param begin a string creating the environment - * @param end a string terminating the environment - */ - virtual void setForEnvironment(const std::string& begin, - const std::string& end) { - _forStart = begin; - _forEnd = end; - } - - /** - * Provides the string used to create the environment for each for loop. - */ - virtual const std::string& getForEnvironmentStart() const { - return _forStart; - } - - /** - * Provides the string used to terminate the environment for each for loop. - */ - virtual const std::string& getForEnvironmentEnd() const { - return _forEnd; - } - - /** - * Defines the Latex environment for each condition. - * - * @param begin a string creating the environment - * @param end a string terminating the environment - */ - virtual void setConditionEnvironment(const std::string& begin, - const std::string& end) { - _conditionStart = begin; - _conditionEnd = end; - } - - /** - * Provides the string used to create the environment for each condition. - */ - virtual const std::string& getConditionEnvironmentStart() const { - return _conditionStart; - } - - /** - * Provides the string used to terminate the environment for each condition. - */ - virtual const std::string& getConditionEnvironmentEnd() const { - return _conditionEnd; - } - - /** - * Defines the Latex environment for each If. - * - * @param begin a string creating the environment - * @param end a string terminating the environment - */ - virtual void setIfEnvironment(const std::string& begin, - const std::string& end) { - _ifStart = begin; - _ifEnd = end; - } - - /** - * Provides the string used to create the environment for each If. - */ - virtual const std::string& getIfEnvironmentStart() const { - return _ifStart; - } - - /** - * Provides the string used to terminate the environment for each If. - */ - virtual const std::string& getIfEnvironmentEnd() const { - return _ifEnd; - } - - /** - * Defines the Latex environment for each else if. - * - * @param begin a string creating the environment - * @param end a string terminating the environment - */ - virtual void setElseIfEnvironment(const std::string& begin, - const std::string& end) { - _elseIfStart = begin; - _elseIfEnd = end; - } - - /** - * Provides the string used to create the environment for each else if. - */ - virtual const std::string& getElseIfEnvironmentStart() const { - return _elseIfStart; - } - - /** - * Provides the string used to terminate the environment for each else if. - */ - virtual const std::string& getElseIfEnvironmentEnd() const { - return _elseIfEnd; - } - - /** - * Defines the Latex environment for each else. - * - * @param begin a string creating the environment - * @param end a string terminating the environment - */ - virtual void setElseEnvironment(const std::string& begin, - const std::string& end) { - _elseStart = begin; - _elseEnd = end; - } - - /** - * Provides the string used to create the environment for each else. - */ - virtual const std::string& getElseEnvironmentStart() const { - return _elseStart; - } - - /** - * Provides the string used to terminate the environment for each else. - */ - virtual const std::string& getElseEnvironmentEnd() const { - return _elseEnd; - } - - /** - * Provides the maximum precision used to print constant values in the - * generated source code - * - * @return the maximum number of digits - */ - virtual size_t getParameterPrecision() const { - return _parameterPrecision; - } - - /** - * Defines the maximum precision used to print constant values in the - * generated source code - * - * @param p the maximum number of digits - */ - virtual void setParameterPrecision(size_t p) { - _parameterPrecision = p; - } - - /** - * Defines whether or not to always enclose the base of a power within - * parenthesis. - * By default the base is only enclosed in parenthesis if it contains of a - * mathematical expression. - * - * @param enclose true to always enclose the base in parenthesis - */ - virtual void setAlwaysEnclosePowBase(bool enclose) { - _powBaseEnclose = enclose; - } - - /** - * Whether or not to always enclose the base of a power within - * parenthesis. - * - * @return true if the base is always enclosed within parenthesis - */ - virtual bool isAlwaysEnclosePowBase() const { - return _powBaseEnclose; - } - - - /** - * Provides the operator used to define multiplications. - * The default is an empty space. - * - * @note Multiplications of constant parameters use a different - * multiplication markup string - */ - inline const std::string& getMultiplicationOperator() const { - return _multOpStr; - } - - /** - * Defines the operator used for multiplications. - * The default is an empty space. - * Other common alternatives are "\cdot" and "\times". - * - * @note Multiplications of constant parameters use a different - * multiplication operator - */ - inline void setMultiplicationOperator(const std::string& multOpStr) { - _multOpStr = multOpStr; - } - - /** - * Provides the operator used for multiplication of constant parameters. - * The default is "\times". - */ - inline const std::string& getMultiplicationConstParOperator() const { - return _multValOpStr; - } - - /** - * Defines the operator used for multiplication of constant parameters. - * The default is "\times". - * Another common alternative is "\cdot". - * Please take into account that numbers too close together are difficult - * to distinguish. - */ - inline void setMultiplicationConstParOperator(const std::string& multValOpStr) { - _multValOpStr = multValOpStr; - } - - virtual void setMaxAssignmentsPerFunction(size_t maxAssignmentsPerFunction, - std::map* sources) { - _maxAssignmentsPerFile = maxAssignmentsPerFunction; - _sources = sources; - } - - inline virtual ~LanguageLatex() { - } - - /*************************************************************************** - * STATIC - **************************************************************************/ - static inline void printIndexCondExpr(std::ostringstream& out, - const std::vector& info, - const std::string& index) { - CPPADCG_ASSERT_KNOWN(info.size() > 1 && info.size() % 2 == 0, "Invalid number of information elements for an index condition expression operation"); - - size_t infoSize = info.size(); - for (size_t e = 0; e < infoSize; e += 2) { - if (e > 0) { - out << " \\vee "; // or - } - size_t min = info[e]; - size_t max = info[e + 1]; - if (min == max) { - out << index << " == " << min; - } else if (min == 0) { - out << index << " \\le " << max; - } else if (max == std::numeric_limits::max()) { - out << min << " \\le " << index; - } else { - if (infoSize != 2) - out << "("; - - if (max - min == 1) - out << min << " == " << index << " \\vee " << index << " == " << max; - else - out << min << " \\le " << index << " \\wedge" << index << " \\le " << max; - - if (infoSize != 2) - out << ")"; - } - } - } - - /*************************************************************************** - * - **************************************************************************/ - - inline void printStaticIndexArray(std::ostringstream& os, - const std::string& name, - const std::vector& values); - - inline void printStaticIndexMatrix(std::ostringstream& os, - const std::string& name, - const std::map >& values); - - /*************************************************************************** - * index patterns - **************************************************************************/ - static inline void generateNames4RandomIndexPatterns(const std::set& randomPatterns); - - inline void printRandomIndexPatternDeclaration(std::ostringstream& os, - const std::string& identation, - const std::set& randomPatterns); - - static inline std::string indexPattern2String(const IndexPattern& ip, - const Node& index); - - static inline std::string indexPattern2String(const IndexPattern& ip, - const std::vector& indexes); - - static inline std::string linearIndexPattern2String(const LinearIndexPattern& lip, - const Node& index); - - /*************************************************************************** - * protected - **************************************************************************/ -protected: - - virtual void generateSourceCode(std::ostream& out, - const std::unique_ptr >& info) override { - - const bool multiFile = _maxAssignmentsPerFile > 0 && _sources != nullptr; - - // clean up - _code.str(""); - _ss.str(""); - _indentationLevel = 0; - _temporary.clear(); - _inEquationEnv = false; - auxArrayName_ = ""; - _currentLoops.clear(); - - - // save some info - _info = info.get(); - _independentSize = info->independent.size(); - _dependent = &info->dependent; - _nameGen = &info->nameGen; - _minTemporaryVarID = info->minTemporaryVarID; - const ArrayWrapper >& dependent = info->dependent; - const std::vector& variableOrder = info->variableOrder; - - _tmpArrayValues.resize(_nameGen->getMaxTemporaryArrayVariableID()); - std::fill(_tmpArrayValues.begin(), _tmpArrayValues.end(), nullptr); - _tmpSparseArrayValues.resize(_nameGen->getMaxTemporarySparseArrayVariableID()); - std::fill(_tmpSparseArrayValues.begin(), _tmpSparseArrayValues.end(), nullptr); - - /** - * generate index array names (might be used for variable names) - */ - generateNames4RandomIndexPatterns(info->indexRandomPatterns); - - /** - * generate variable names - */ - //generate names for the independent variables - for (size_t j = 0; j < _independentSize; j++) { - Node& op = *info->independent[j]; - if (op.getName() == nullptr) { - op.setName(_nameGen->generateIndependent(op, getVariableID(op))); - } - } - - // generate names for the dependent variables (must be after naming independents) - for (size_t i = 0; i < dependent.size(); i++) { - Node* node = dependent[i].getOperationNode(); - if (node != nullptr && node->getOperationType() != CGOpCode::LoopEnd && node->getName() == nullptr) { - if (node->getOperationType() == CGOpCode::LoopIndexedDep) { - size_t pos = node->getInfo()[0]; - const IndexPattern* ip = info->loopDependentIndexPatterns[pos]; - node->setName(_nameGen->generateIndexedDependent(*node, getVariableID(*node), *ip)); - - } else { - node->setName(_nameGen->generateDependent(i)); - } - } - } - - /** - * function variable declaration - */ - const std::vector& indArg = _nameGen->getIndependent(); - const std::vector& depArg = _nameGen->getDependent(); - const std::vector& tmpArg = _nameGen->getTemporary(); - CPPADCG_ASSERT_KNOWN(indArg.size() > 0 && depArg.size() > 0, - "There must be at least one dependent and one independent argument"); - CPPADCG_ASSERT_KNOWN(tmpArg.size() == 3, - "There must be three temporary variables"); - - auxArrayName_ = tmpArg[1].name + "p"; - - /** - * Determine the dependent variables that result from the same operations - */ - // dependent variables indexes that are copies of other dependent variables - std::set dependentDuplicates; - - for (size_t i = 0; i < dependent.size(); i++) { - Node* node = dependent[i].getOperationNode(); - if (node != nullptr) { - CGOpCode type = node->getOperationType(); - if (type != CGOpCode::Inv && type != CGOpCode::LoopEnd) { - size_t varID = getVariableID(*node); - if (varID > 0) { - std::map::const_iterator it2 = _dependentIDs.find(varID); - if (it2 == _dependentIDs.end()) { - _dependentIDs[getVariableID(*node)] = i; - } else { - // there can be several dependent variables with the same ID - dependentDuplicates.insert(i); - } - } - } - } - } - - // the names of local functions - std::vector inputLatexFiles; - if (multiFile) { - inputLatexFiles.reserve(variableOrder.size() / _maxAssignmentsPerFile); - } - - /** - * non-constant variables - */ - if (variableOrder.size() > 0) { - // generate names for temporary variables - for (Node* node : variableOrder) { - CGOpCode op = node->getOperationType(); - if (!isDependent(*node) && op != CGOpCode::IndexDeclaration) { - // variable names for temporaries must always be created since they might have been used before with a different name/id - if (requiresVariableName(*node) && op != CGOpCode::ArrayCreation && op != CGOpCode::SparseArrayCreation) { - node->setName(_nameGen->generateTemporary(*node, getVariableID(*node))); - } else if (op == CGOpCode::ArrayCreation) { - node->setName(_nameGen->generateTemporaryArray(*node, getVariableID(*node))); - } else if (op == CGOpCode::SparseArrayCreation) { - node->setName(_nameGen->generateTemporarySparseArray(*node, getVariableID(*node))); - } - } - } - - /** - * Source code generation magic! - */ - if (info->zeroDependents) { - // zero initial values - const std::vector& depArg = _nameGen->getDependent(); - if (!depArg.empty()) - checkEquationEnvStart(); - for (size_t i = 0; i < depArg.size(); i++) { - _code << _startAlgLine << _startEq; - const FuncArgument& a = depArg[i]; - if (a.array) { - _code << a.name; - } else { - _code << _startDepVar << _nameGen->generateDependent(i) << _endDepVar; - } - _code << _assignStr; - printParameter(Base(0.0)); - _code << _endEq << _endAlgLine << _endline; - } - } - - size_t assignCount = 0; - for (Node* it : variableOrder) { - // check if a new function should start - if (assignCount >= _maxAssignmentsPerFile && multiFile && _currentLoops.empty()) { - assignCount = 0; - saveLocalFunction(inputLatexFiles, inputLatexFiles.empty() && info->zeroDependents); - } - - Node& node = *it; - - // a dependent variable assigned by a loop does require any source code (its done inside the loop) - if (node.getOperationType() == CGOpCode::DependentRefRhs) { - continue; // nothing to do (this operation is right hand side only) - } else if (node.getOperationType() == CGOpCode::TmpDcl) { // temporary variable declaration does not need any source code here - continue; // nothing to do (bogus operation) - } - - assignCount += printAssignment(node); - } - - if (inputLatexFiles.size() > 0 && assignCount > 0) { - assignCount = 0; - saveLocalFunction(inputLatexFiles, false); - } - } - - if (!inputLatexFiles.empty()) { - /** - * Create the master latex file which inputs the other files - */ - CPPADCG_ASSERT_KNOWN(tmpArg[0].array, - "The temporary variables must be saved in an array in order to generate multiple functions"); - printAlgorithmFileStart(_code); - for (size_t i = 0; i < inputLatexFiles.size(); i++) { - _code << "\\input{" << inputLatexFiles[i] << "}" << _endline; - } - printAlgorithmFileEnd(_code); - } - - // dependent duplicates - if (dependentDuplicates.size() > 0) { - _code << "% variable duplicates: " << dependentDuplicates.size() << _endline; - - checkEquationEnvStart(); - for (size_t index : dependentDuplicates) { - const CG& dep = (*_dependent)[index]; - std::string varName = _nameGen->generateDependent(index); - const std::string& origVarName = *dep.getOperationNode()->getName(); - - _code << _startAlgLine << _startEq - << _startDepVar << varName << _endDepVar - << _assignStr - << _startDepVar << origVarName << _endDepVar; - printAssignmentEnd(); - } - } - - // constant dependent variables - bool commentWritten = false; - for (size_t i = 0; i < dependent.size(); i++) { - if (dependent[i].isParameter()) { - if (!_ignoreZeroDepAssign || !dependent[i].isIdenticalZero()) { - if (!commentWritten) { - _code << "% dependent variables without operations" << _endline; - commentWritten = true; - } - checkEquationEnvStart(); - - std::string varName = _nameGen->generateDependent(i); - _code << _startAlgLine << _startEq - << _startDepVar << varName << _endDepVar << _assignStr; - printParameter(dependent[i].getValue()); - printAssignmentEnd(); - } - } else if (dependent[i].getOperationNode()->getOperationType() == CGOpCode::Inv) { - if (!commentWritten) { - _code << "% dependent variables without operations" << _endline; - commentWritten = true; - } - checkEquationEnvStart(); - - std::string varName = _nameGen->generateDependent(i); - const std::string& indepName = *dependent[i].getOperationNode()->getName(); - _code << _startAlgLine << _startEq - << _startDepVar << varName << _endDepVar - << _assignStr - << _startIndepVar << indepName << _endIndepVar; - printAssignmentEnd(*dependent[i].getOperationNode()); - } - } - - checkEquationEnvEnd(); - - /** - * encapsulate the code in a function - */ - if (inputLatexFiles.empty()) { - // a single source file - printAlgorithmFileStart(_ss); - _ss << _code.str(); - printAlgorithmFileEnd(_ss); - - out << _ss.str(); - - if (_sources != nullptr) { - (*_sources)[_filename + ".tex"] = _ss.str(); - } - } else { - // there are multiple source files (this last one is the master) - (*_sources)[_filename + ".tex"] = _code.str(); - } - - } - - inline size_t getVariableID(const Node& node) const { - return _info->varId[node]; - } - - inline virtual void printAlgorithmFileStart(std::ostream& out) { - out << "% Latex source file for '" << _filename << "' (automatically generated by CppADCodeGen)" << _endline; - out << _algFileStart << _endline; - } - - inline virtual void printAlgorithmFileEnd(std::ostream& out) { - out << _algFileEnd; - } - - inline virtual void checkEquationEnvStart() { - if (!_inEquationEnv) { - _code << _startEqBlock << _endline; - _inEquationEnv = true; - } - } - - inline virtual void checkEquationEnvEnd() { - if (_inEquationEnv) { - _code << _endEqBlock << _endline; - _inEquationEnv = false; - } - } - - inline unsigned printAssignment(Node& node) { - return printAssignment(node, node); - } - - inline unsigned printAssignment(Node& nodeName, - const Arg& nodeRhs) { - if (nodeRhs.getOperation() != nullptr) { - return printAssignment(nodeName, *nodeRhs.getOperation()); - } else { - printAssignmentStart(nodeName); - printParameter(*nodeRhs.getParameter()); - printAssignmentEnd(nodeName); - return 1; - } - } - - inline unsigned printAssignment(Node& nodeName, - Node& nodeRhs) { - bool createsVar = directlyAssignsVariable(nodeRhs); // do we need to do the assignment here? - if (!createsVar) { - printAssignmentStart(nodeName); - } - unsigned lines = printExpressionNoVarCheck(nodeRhs); - if (!createsVar) { - printAssignmentEnd(nodeRhs); - } - - if (nodeRhs.getOperationType() == CGOpCode::ArrayElement) { - Node* array = nodeRhs.getArguments()[0].getOperation(); - size_t arrayId = getVariableID(*array); - size_t pos = nodeRhs.getInfo()[0]; - if (array->getOperationType() == CGOpCode::ArrayCreation) - _tmpArrayValues[arrayId - 1 + pos] = nullptr; // this could probably be removed! - else - _tmpSparseArrayValues[arrayId - 1 + pos] = nullptr; // this could probably be removed! - } - - return lines; - } - - inline virtual void printAssignmentStart(Node& op) { - printAssignmentStart(op, createVariableName(op), isDependent(op)); - } - - inline virtual void printAssignmentStart(Node& node, const std::string& varName, bool isDep) { - if (!isDep) { - _temporary[getVariableID(node)] = &node; - } - - checkEquationEnvStart(); - - _code << _startAlgLine << _startEq; - if (isDep) - _code << _startDepVar << varName << _endDepVar; - else - _code << _startVar << varName << _endVar; - - CGOpCode op = node.getOperationType(); - if (op == CGOpCode::DependentMultiAssign || (op == CGOpCode::LoopIndexedDep && node.getInfo()[1] == 1)) { - _code << " += "; - } else { - _code << _assignStr; - } - } - - inline virtual void printAssignmentEnd() { - _code << _endEq << _endAlgLine << _endline; - } - - inline virtual void printAssignmentEnd(Node& op) { - printAssignmentEnd(); - } - - virtual void saveLocalFunction(std::vector& localFuncNames, - bool zeroDependentArray) { - _ss << _filename << "__part_" << (localFuncNames.size() + 1); - std::string funcName = _ss.str(); - _ss.str(""); - - // loop indexes - _nameGen->prepareCustomFunctionVariables(_ss); - _ss << _code.str(); - _nameGen->finalizeCustomFunctionVariables(_ss); - - (*_sources)[funcName + ".tex"] = _ss.str(); - localFuncNames.push_back(funcName); - - _code.str(""); - _ss.str(""); - } - - virtual bool createsNewVariable(const Node& var, - size_t totalUseCount) const override { - CGOpCode op = var.getOperationType(); - if (totalUseCount > 1) { - return op != CGOpCode::ArrayElement && op != CGOpCode::Index && op != CGOpCode::IndexDeclaration && op != CGOpCode::Tmp; - } else { - return ( op == CGOpCode::ArrayCreation || - op == CGOpCode::SparseArrayCreation || - op == CGOpCode::AtomicForward || - op == CGOpCode::AtomicReverse || - op == CGOpCode::ComLt || - op == CGOpCode::ComLe || - op == CGOpCode::ComEq || - op == CGOpCode::ComGe || - op == CGOpCode::ComGt || - op == CGOpCode::ComNe || - op == CGOpCode::LoopIndexedDep || - op == CGOpCode::LoopIndexedTmp || - op == CGOpCode::IndexAssign || - op == CGOpCode::Assign) && - op != CGOpCode::CondResult; - } - } - - virtual bool requiresVariableName(const Node& var) const { - CGOpCode op = var.getOperationType(); - return (_info->totalUseCount.get(var) > 1 && - op != CGOpCode::AtomicForward && - op != CGOpCode::AtomicReverse && - op != CGOpCode::LoopStart && - op != CGOpCode::LoopEnd && - op != CGOpCode::Index && - op != CGOpCode::IndexAssign && - op != CGOpCode::StartIf && - op != CGOpCode::ElseIf && - op != CGOpCode::Else && - op != CGOpCode::EndIf && - op != CGOpCode::CondResult && - op != CGOpCode::LoopIndexedTmp && - op != CGOpCode::Tmp); - } - - /** - * Whether or not this operation assign its expression to a variable by - * itself. - * - * @param var the operation node - * @return - */ - virtual bool directlyAssignsVariable(const Node& var) const { - CGOpCode op = var.getOperationType(); - return isCondAssign(op) || - op == CGOpCode::ArrayCreation || - op == CGOpCode::SparseArrayCreation || - op == CGOpCode::AtomicForward || - op == CGOpCode::AtomicReverse || - op == CGOpCode::DependentMultiAssign || - op == CGOpCode::LoopStart || - op == CGOpCode::LoopEnd || - op == CGOpCode::IndexAssign || - op == CGOpCode::StartIf || - op == CGOpCode::ElseIf || - op == CGOpCode::Else || - op == CGOpCode::EndIf || - op == CGOpCode::CondResult || - op == CGOpCode::IndexDeclaration; - } - - virtual bool requiresVariableArgument(enum CGOpCode op, size_t argIndex) const override { - return op == CGOpCode::CondResult; - } - - inline const std::string& createVariableName(Node& var) { - CGOpCode op = var.getOperationType(); - CPPADCG_ASSERT_UNKNOWN(getVariableID(var) > 0); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::AtomicForward); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::AtomicReverse); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::LoopStart); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::LoopEnd); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::Index); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::IndexAssign); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::IndexDeclaration); - - if (var.getName() == nullptr) { - if (op == CGOpCode::ArrayCreation) { - var.setName(_nameGen->generateTemporaryArray(var, getVariableID(var))); - - } else if (op == CGOpCode::SparseArrayCreation) { - var.setName(_nameGen->generateTemporarySparseArray(var, getVariableID(var))); - - } else if (op == CGOpCode::LoopIndexedDep) { - size_t pos = var.getInfo()[0]; - const IndexPattern* ip = _info->loopDependentIndexPatterns[pos]; - var.setName(_nameGen->generateIndexedDependent(var, getVariableID(var), *ip)); - - } else if (op == CGOpCode::LoopIndexedIndep) { - size_t pos = var.getInfo()[1]; - const IndexPattern* ip = _info->loopIndependentIndexPatterns[pos]; - var.setName(_nameGen->generateIndexedIndependent(var, getVariableID(var), *ip)); - - } else if (getVariableID(var) <= _independentSize) { - // independent variable - var.setName(_nameGen->generateIndependent(var, getVariableID(var))); - - } else if (getVariableID(var) < _minTemporaryVarID) { - // dependent variable - std::map::const_iterator it = _dependentIDs.find(getVariableID(var)); - CPPADCG_ASSERT_UNKNOWN(it != _dependentIDs.end()); - - size_t index = it->second; - var.setName(_nameGen->generateDependent(index)); - - } else if (op == CGOpCode::LoopIndexedTmp || op == CGOpCode::Tmp) { - CPPADCG_ASSERT_KNOWN(var.getArguments().size() >= 1, "Invalid number of arguments for loop indexed temporary operation"); - Node* tmpVar = var.getArguments()[0].getOperation(); - CPPADCG_ASSERT_KNOWN(tmpVar != nullptr && tmpVar->getOperationType() == CGOpCode::TmpDcl, "Invalid arguments for loop indexed temporary operation"); - return createVariableName(*tmpVar); - - } else { - // temporary variable - var.setName(_nameGen->generateTemporary(var, getVariableID(var))); - } - } - - - return *var.getName(); - } - - virtual bool requiresVariableDependencies() const override { - return false; - } - - virtual void printIndependentVariableName(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 0, "Invalid number of arguments for independent variable"); - - _code << _startIndepVar << _nameGen->generateIndependent(op, getVariableID(op)) << _endIndepVar; - } - - virtual unsigned print(const Arg& arg) { - if (arg.getOperation() != nullptr) { - // expression - return printExpression(*arg.getOperation()); - } else { - // parameter - printParameter(*arg.getParameter()); - return 1; - } - } - - virtual unsigned printExpression(Node& node) { - if (getVariableID(node) > 0) { - const std::string& name = createVariableName(node); // use variable name - - CGOpCode op = node.getOperationType(); - if (getVariableID(node) >= _minTemporaryVarID || op == CGOpCode::ArrayCreation || op == CGOpCode::SparseArrayCreation || op == CGOpCode::LoopIndexedDep || op == CGOpCode::LoopIndexedIndep) { - - _code << _startVar << name << _endVar; - - } else if (getVariableID(node) <= _independentSize) { - // independent variable - _code << _startIndepVar << name << _endIndepVar; - - } else { - // dependent variable - _code << _startDepVar << name << _endDepVar; - - } - - return 1; - } else { - // print expression code - return printExpressionNoVarCheck(node); - } - } - - virtual unsigned printExpressionNoVarCheck(Node& node) { - CGOpCode op = node.getOperationType(); - switch (op) { - case CGOpCode::ArrayCreation: - printArrayCreationOp(node); - break; - case CGOpCode::SparseArrayCreation: - printSparseArrayCreationOp(node); - break; - case CGOpCode::ArrayElement: - printArrayElementOp(node); - break; - case CGOpCode::Assign: - return printAssignOp(node); - - case CGOpCode::Abs: - case CGOpCode::Acos: - case CGOpCode::Asin: - case CGOpCode::Atan: - case CGOpCode::Cosh: - case CGOpCode::Cos: - case CGOpCode::Exp: - case CGOpCode::Log: - case CGOpCode::Sign: - case CGOpCode::Sinh: - case CGOpCode::Sin: - case CGOpCode::Sqrt: - case CGOpCode::Tanh: - case CGOpCode::Tan: - printUnaryFunction(node); - break; - case CGOpCode::AtomicForward: // atomicFunction.forward(q, p, vx, vy, tx, ty) - printAtomicForwardOp(node); - break; - case CGOpCode::AtomicReverse: // atomicFunction.reverse(p, tx, ty, px, py) - printAtomicReverseOp(node); - break; - case CGOpCode::Add: - printOperationAdd(node); - break; - case CGOpCode::Alias: - return printOperationAlias(node); - - case CGOpCode::ComLt: - case CGOpCode::ComLe: - case CGOpCode::ComEq: - case CGOpCode::ComGe: - case CGOpCode::ComGt: - case CGOpCode::ComNe: - printConditionalAssignment(node); - break; - case CGOpCode::Div: - printOperationDiv(node); - break; - case CGOpCode::Inv: - printIndependentVariableName(node); - break; - case CGOpCode::Mul: - printOperationMul(node); - break; - case CGOpCode::Pow: - printPowFunction(node); - break; - case CGOpCode::Pri: - // do nothing - break; - case CGOpCode::Sub: - printOperationMinus(node); - break; - - case CGOpCode::UnMinus: - printOperationUnaryMinus(node); - break; - - case CGOpCode::DependentMultiAssign: - return printDependentMultiAssign(node); - - case CGOpCode::Index: - return 0; // nothing to do - case CGOpCode::IndexAssign: - printIndexAssign(node); - break; - case CGOpCode::IndexDeclaration: - return 0; // already done - - case CGOpCode::LoopStart: - printLoopStart(node); - break; - case CGOpCode::LoopIndexedIndep: - printLoopIndexedIndep(node); - break; - case CGOpCode::LoopIndexedDep: - printLoopIndexedDep(node); - break; - case CGOpCode::LoopIndexedTmp: - printLoopIndexedTmp(node); - break; - case CGOpCode::TmpDcl: - // nothing to do - return 0; - case CGOpCode::Tmp: - printTmpVar(node); - break; - case CGOpCode::LoopEnd: - printLoopEnd(node); - break; - case CGOpCode::IndexCondExpr: - printIndexCondExprOp(node); - break; - case CGOpCode::StartIf: - printStartIf(node); - break; - case CGOpCode::ElseIf: - printElseIf(node); - break; - case CGOpCode::Else: - printElse(node); - break; - case CGOpCode::EndIf: - printEndIf(node); - break; - case CGOpCode::CondResult: - printCondResult(node); - break; - case CGOpCode::UserCustom: - printUserCustom(node); - break; - default: - throw CGException("Unknown operation code '", op, "'."); - } - return 1; - } - - virtual unsigned printAssignOp(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 1, "Invalid number of arguments for assign operation"); - - return print(node.getArguments()[0]); - } - - virtual void printUnaryFunction(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 1, "Invalid number of arguments for unary function"); - - switch (op.getOperationType()) { - case CGOpCode::Abs: - _code << "\\abs{"; - print(op.getArguments()[0]); - _code << "}"; - return; - case CGOpCode::Acos: - _code << "\\arccos"; - break; - case CGOpCode::Asin: - _code << "\\arcsin"; - break; - case CGOpCode::Atan: - _code << "\\arctan"; - break; - case CGOpCode::Cosh: - _code << "\\cosh"; - break; - case CGOpCode::Cos: - _code << "\\cos"; - break; - case CGOpCode::Exp: - _code << "\\exp"; ///////////////////////////////////////// consider using superscript - break; - case CGOpCode::Log: - _code << "\\ln"; - break; - case CGOpCode::Sinh: - _code << "\\sinh"; - break; - case CGOpCode::Sign: - _code << "\\operatorname{sgn}"; - break; - case CGOpCode::Sin: - _code << "\\sin"; - break; - case CGOpCode::Sqrt: - _code << "\\sqrt{"; - print(op.getArguments()[0]); - _code << "}"; - return; - case CGOpCode::Tanh: - _code << "\\tanh"; - break; - case CGOpCode::Tan: - _code << "\\tan"; - break; - default: - throw CGException("Unknown function name for operation code '", op.getOperationType(), "'."); - } - - _code << "\\mathopen{}\\left("; - print(op.getArguments()[0]); - _code << "\\right)\\mathclose{}"; - } - - virtual void printPowFunction(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for pow() function"); - - auto encloseInParentheses = [this](const Node* node) { - while (node != nullptr) { - if (getVariableID(*node) != 0) - return false; - if (node->getOperationType() == CGOpCode::Alias) - node = node->getArguments()[0].getOperation(); - else - break; - } - return node != nullptr && - getVariableID(*node) == 0 && - !isFunction(node->getOperationType()); - }; - - bool encloseBase = _powBaseEnclose || encloseInParentheses(op.getArguments()[0].getOperation()); - bool encloseExpo = encloseInParentheses(op.getArguments()[1].getOperation()); - - _code << "{"; - if (encloseBase) - _code << "\\left("; - print(op.getArguments()[0]); - if (encloseBase) - _code << "\\right)"; - _code << "}^{"; - if (encloseExpo) - _code << "\\left("; - print(op.getArguments()[1]); - if (encloseExpo) - _code << "\\right)"; - _code << "}"; - } - - virtual unsigned printOperationAlias(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 1, "Invalid number of arguments for alias"); - return print(op.getArguments()[0]); - } - - virtual void printOperationAdd(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for addition"); - - const Arg& left = op.getArguments()[0]; - const Arg& right = op.getArguments()[1]; - - if(right.getParameter() == nullptr || (*right.getParameter() >= 0)) { - print(left); - _code << " + "; - print(right); - } else { - // right has a negative parameter so we would get v0 + -v1 - print(left); - _code << " - "; - printParameter(-*right.getParameter()); // make it positive - } - } - - virtual void printOperationMinus(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for subtraction"); - - const Arg& left = op.getArguments()[0]; - const Arg& right = op.getArguments()[1]; - - if(right.getParameter() == nullptr || (*right.getParameter() >= 0)) { - bool encloseRight = encloseInParenthesesMul(right); - - print(left); - _code << " - "; - if (encloseRight) { - _code << "\\left("; - } - print(right); - if (encloseRight) { - _code << "\\right)"; - } - } else { - // right has a negative parameter so we would get v0 - -v1 - print(left); - _code << " + "; - printParameter(-*right.getParameter()); // make it positive - } - } - - virtual void printOperationDiv(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for division"); - - const Arg& left = op.getArguments()[0]; - const Arg& right = op.getArguments()[1]; - - - _code << "\\frac{"; - print(left); - _code << "}{"; - print(right); - _code << "}"; - - } - - inline bool encloseInParenthesesMul(const Arg& arg) const { - if (arg.getParameter() != nullptr) { - return ((*arg.getParameter()) < 0); - } else { - return encloseInParenthesesMul(arg.getOperation()); - } - } - - inline bool encloseInParenthesesMul(const Node* node) const { - while (node != nullptr) { - if (getVariableID(*node) != 0) { - return false; - } else if (node->getOperationType() == CGOpCode::Alias) { - node = node->getArguments()[0].getOperation(); - } else { - break; - } - } - return node != nullptr && - getVariableID(*node) == 0 && - node->getOperationType() != CGOpCode::Div && - node->getOperationType() != CGOpCode::Mul && - !isFunction(node->getOperationType()); - } - - virtual void printOperationMul(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for multiplication"); - - const Arg& left = op.getArguments()[0]; - const Arg& right = op.getArguments()[1]; - - bool encloseLeft = encloseInParenthesesMul(left); - bool encloseRight = encloseInParenthesesMul(right); - - auto isNumber = [this](const Node* node, int pos) -> bool { - while (node != nullptr) { - if(getVariableID(*node) != 0) { - return false; - } - CGOpCode op = node->getOperationType(); - if (op == CGOpCode::Alias) { - node = node->getArguments()[0].getOperation(); - continue; - } else if (op == CGOpCode::Mul) { - node = node->getArguments()[pos].getOperation(); - } else if (pos == 0 && op == CGOpCode::Pow) { - node = node->getArguments()[0].getOperation(); - } else { - return false; - } - } - return true; // a constant number - }; - - if (encloseLeft) { - _code << "\\left("; - } - print(left); - if (encloseLeft) { - _code << "\\right)"; - } - - if (isNumber(left.getOperation(), 1) && isNumber(right.getOperation(), 0)) - _code << _multValOpStr; // numbers too close together are difficult to distinguish - else - _code << _multOpStr; // e.g. invisible times - - if (encloseRight) { - _code << "\\left("; - } - print(right); - if (encloseRight) { - _code << "\\right)"; - } - } - - virtual void printOperationUnaryMinus(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 1, "Invalid number of arguments for unary minus"); - - const Arg& arg = op.getArguments()[0]; - - bool enclose = encloseInParenthesesMul(arg); - - _code << "-"; - if (enclose) { - _code << "\\left("; - } - print(arg); - if (enclose) { - _code << "\\right)"; - } - } - - virtual void printConditionalAssignment(Node& node) { - CPPADCG_ASSERT_UNKNOWN(getVariableID(node) > 0); - - const std::vector& args = node.getArguments(); - const Arg &left = args[0]; - const Arg &right = args[1]; - const Arg &trueCase = args[2]; - const Arg &falseCase = args[3]; - - bool isDep = isDependent(node); - const std::string& varName = createVariableName(node); - - if ((trueCase.getParameter() != nullptr && falseCase.getParameter() != nullptr && *trueCase.getParameter() == *falseCase.getParameter()) || - (trueCase.getOperation() != nullptr && falseCase.getOperation() != nullptr && trueCase.getOperation() == falseCase.getOperation())) { - // true and false cases are the same - printAssignmentStart(node, varName, isDep); - print(trueCase); - printAssignmentEnd(node); - } else { - checkEquationEnvEnd(); - - _code << _ifStart; - _code << _conditionStart; - print(left); - _code << " " << getComparison(node.getOperationType()) << " "; - print(right); - _code << _conditionEnd; - _code << _endline; - //checkEquationEnvStart(); // no need - printAssignmentStart(node, varName, isDep); - print(trueCase); - printAssignmentEnd(node); - checkEquationEnvEnd(); - _code << _ifEnd << _endline; - _code << _elseStart << _endline; // else - //checkEquationEnvStart(); // no need - printAssignmentStart(node, varName, isDep); - print(falseCase); - printAssignmentEnd(node); - checkEquationEnvEnd(); - _code << _elseEnd << _endline; // end if - } - } - - inline bool isSameArgument(const Arg& newArg, - const Arg* oldArg) { - if (oldArg != nullptr) { - if (oldArg->getParameter() != nullptr) { - if (newArg.getParameter() != nullptr) { - return (*newArg.getParameter() == *oldArg->getParameter()); - } - } else { - return (newArg.getOperation() == oldArg->getOperation()); - } - } - return false; - } - - virtual void printArrayCreationOp(Node& op); - - virtual void printSparseArrayCreationOp(Node& op); - - inline void printArrayStructInit(const std::string& dataArrayName, - size_t pos, - const std::vector& arrays, - size_t k); - - inline void printArrayStructInit(const std::string& dataArrayName, - Node& array); - - inline void markArrayChanged(Node& ty); - - inline size_t printArrayCreationUsingLoop(size_t startPos, - Node& array, - size_t startj, - std::vector& tmpArrayValues); - - inline std::string getTempArrayName(const Node& op); - - virtual void printArrayElementOp(Node& op); - - virtual void printAtomicForwardOp(Node& atomicFor) { - CPPADCG_ASSERT_KNOWN(atomicFor.getInfo().size() == 3, "Invalid number of information elements for atomic forward operation"); - int q = atomicFor.getInfo()[1]; - int p = atomicFor.getInfo()[2]; - size_t p1 = p + 1; - const std::vector& opArgs = atomicFor.getArguments(); - CPPADCG_ASSERT_KNOWN(opArgs.size() == p1 * 2, "Invalid number of arguments for atomic forward operation"); - - size_t id = atomicFor.getInfo()[0]; - std::vector tx(p1), ty(p1); - for (size_t k = 0; k < p1; k++) { - tx[k] = opArgs[0 * p1 + k].getOperation(); - ty[k] = opArgs[1 * p1 + k].getOperation(); - } - - CPPADCG_ASSERT_KNOWN(tx[0]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - CPPADCG_ASSERT_KNOWN(p == 0 || tx[1]->getOperationType() == CGOpCode::SparseArrayCreation, "Invalid array type"); - CPPADCG_ASSERT_KNOWN(ty[p]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - - // tx - for (size_t k = 0; k < p1; k++) { - printArrayStructInit(_ATOMIC_TX, k, tx, k); - } - // ty - printArrayStructInit(_ATOMIC_TY, *ty[p]); - _ss.str(""); - - _code << _startAlgLine << _startEq - << _info->atomicFunctionId2Name.at(id) << ".forward(" - << q << ", " << p << ", " - << _ATOMIC_TX << ", &" << _ATOMIC_TY << ")" - << _endEq << _endAlgLine << _endline; - - /** - * the values of ty are now changed - */ - markArrayChanged(*ty[p]); - } - - virtual void printAtomicReverseOp(Node& atomicRev) { - CPPADCG_ASSERT_KNOWN(atomicRev.getInfo().size() == 2, "Invalid number of information elements for atomic reverse operation"); - int p = atomicRev.getInfo()[1]; - size_t p1 = p + 1; - const std::vector& opArgs = atomicRev.getArguments(); - CPPADCG_ASSERT_KNOWN(opArgs.size() == p1 * 4, "Invalid number of arguments for atomic reverse operation"); - - size_t id = atomicRev.getInfo()[0]; - std::vector tx(p1), px(p1), py(p1); - for (size_t k = 0; k < p1; k++) { - tx[k] = opArgs[0 * p1 + k].getOperation(); - px[k] = opArgs[2 * p1 + k].getOperation(); - py[k] = opArgs[3 * p1 + k].getOperation(); - } - - CPPADCG_ASSERT_KNOWN(tx[0]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - CPPADCG_ASSERT_KNOWN(p == 0 || tx[1]->getOperationType() == CGOpCode::SparseArrayCreation, "Invalid array type"); - - CPPADCG_ASSERT_KNOWN(px[0]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - - CPPADCG_ASSERT_KNOWN(py[0]->getOperationType() == CGOpCode::SparseArrayCreation, "Invalid array type"); - CPPADCG_ASSERT_KNOWN(p == 0 || py[1]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - - // tx - for (size_t k = 0; k < p1; k++) { - printArrayStructInit(_ATOMIC_TX, k, tx, k); - } - // py - for (size_t k = 0; k < p1; k++) { - printArrayStructInit(_ATOMIC_PY, k, py, k); - } - // px - printArrayStructInit(_ATOMIC_PX, *px[0]); - _ss.str(""); - - _code << _startAlgLine << _startEq - << _info->atomicFunctionId2Name.at(id) << ".reverse(" - << p << ", " - << _ATOMIC_TX << ", &" << _ATOMIC_PX << ", " << _ATOMIC_PY << ")" - << _endEq << _endAlgLine << _endline; - - /** - * the values of px are now changed - */ - markArrayChanged(*px[0]); - } - - virtual unsigned printDependentMultiAssign(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::DependentMultiAssign, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() > 0, "Invalid number of arguments"); - - const std::vector& args = node.getArguments(); - for (size_t a = 0; a < args.size(); a++) { - bool useArg = false; - const Arg& arg = args[a]; - if (arg.getParameter() != nullptr) { - useArg = true; - } else { - CGOpCode op = arg.getOperation()->getOperationType(); - useArg = op != CGOpCode::DependentRefRhs && op != CGOpCode::LoopEnd && op != CGOpCode::EndIf; - } - - if (useArg) { - printAssignment(node, arg); // ignore other arguments! - return 1; - } - } - return 0; - } - - virtual void printLoopStart(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopStart, "Invalid node type"); - - LoopStartOperationNode& lnode = static_cast&> (node); - _currentLoops.push_back(&lnode); - - const std::string& jj = *lnode.getIndex().getName(); - std::string lastIt; - if (lnode.getIterationCountNode() != nullptr) { - lastIt = *lnode.getIterationCountNode()->getIndex().getName() + " - 1"; - } else { - lastIt = std::to_string(lnode.getIterationCount() - 1); - } - - checkEquationEnvEnd(); - - _code << _forStart << "{$" << jj << _assignStr << "0$ to $" << lastIt << "$}" << _endline; - _indentationLevel++; - } - - virtual void printLoopEnd(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopEnd, "Invalid node type"); - - checkEquationEnvEnd(); - - _indentationLevel--; - - _code << _forEnd << _endline; - - _currentLoops.pop_back(); - } - - virtual void printLoopIndexedDep(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 1, "Invalid number of arguments for loop indexed dependent operation"); - - // LoopIndexedDep - print(node.getArguments()[0]); - } - - virtual void printLoopIndexedIndep(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopIndexedIndep, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getInfo().size() == 1, "Invalid number of information elements for loop indexed independent operation"); - - // CGLoopIndexedIndepOp - size_t pos = node.getInfo()[1]; - const IndexPattern* ip = _info->loopIndependentIndexPatterns[pos]; - _code << _nameGen->generateIndexedIndependent(node, getVariableID(node), *ip); - } - - virtual void printLoopIndexedTmp(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopIndexedTmp, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 2, "Invalid number of arguments for loop indexed temporary operation"); - Node* tmpVar = node.getArguments()[0].getOperation(); - CPPADCG_ASSERT_KNOWN(tmpVar != nullptr && tmpVar->getOperationType() == CGOpCode::TmpDcl, "Invalid arguments for loop indexed temporary operation"); - - print(node.getArguments()[1]); - } - - virtual void printTmpVar(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::Tmp, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() > 0, "Invalid number of arguments for temporary variable usage operation"); - Node* tmpVar = node.getArguments()[0].getOperation(); - CPPADCG_ASSERT_KNOWN(tmpVar != nullptr && tmpVar->getOperationType() == CGOpCode::TmpDcl, "Invalid arguments for loop indexed temporary operation"); - - _code << _startVar << *tmpVar->getName() << _endVar; - } - - virtual void printIndexAssign(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::IndexAssign, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() > 0, "Invalid number of arguments for an index assignment operation"); - - IndexAssignOperationNode& inode = static_cast&> (node); - - checkEquationEnvStart(); - - const IndexPattern& ip = inode.getIndexPattern(); - _code << _startAlgLine << _startEq - << (*inode.getIndex().getName()) - << _assignStr << indexPattern2String(ip, inode.getIndexPatternIndexes()) - << _endEq << _endAlgLine << _endline; - } - - virtual void printIndexCondExprOp(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::IndexCondExpr, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 1, "Invalid number of arguments for an index condition expression operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an index condition expression operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation()->getOperationType() == CGOpCode::Index, "Invalid argument for an index condition expression operation"); - - const std::vector& info = node.getInfo(); - - IndexOperationNode& iterationIndexOp = static_cast&> (*node.getArguments()[0].getOperation()); - const std::string& index = *iterationIndexOp.getIndex().getName(); - - checkEquationEnvStart(); - - printIndexCondExpr(_code, info, index); - } - - virtual void printStartIf(Node& node) { - /** - * the first argument is the condition, following arguments are - * just extra dependencies that must be defined outside the if - */ - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::StartIf, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 1, "Invalid number of arguments for an 'if start' operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an 'if start' operation"); - - checkEquationEnvEnd(); - - _code << _ifStart; - //checkEquationEnvStart(); // no need - _code << _conditionStart; - printIndexCondExprOp(*node.getArguments()[0].getOperation()); - checkEquationEnvEnd(); - _code << _conditionEnd; - _code << _endline; - - _indentationLevel++; - } - - virtual void printElseIf(Node& node) { - /** - * the first argument is the condition, the second argument is the - * if start node, the following arguments are assignments in the - * previous if branch - */ - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::ElseIf, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 2, "Invalid number of arguments for an 'else if' operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an 'else if' operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[1].getOperation() != nullptr, "Invalid argument for an 'else if' operation"); - - checkEquationEnvEnd(); - _indentationLevel--; - - // close previous environment - CGOpCode nType = node.getArguments()[0].getOperation()->getOperationType(); - if (nType == CGOpCode::StartIf) { - _code << _ifEnd << _endline; - } else if (nType == CGOpCode::ElseIf) { - _code << _elseIfEnd << _endline; - } - - // start new else if - _code << _elseIfStart; - _code << _conditionStart; - //checkEquationEnvStart(); // no need - printIndexCondExprOp(*node.getArguments()[1].getOperation()); - checkEquationEnvEnd(); - _code << _conditionEnd; - _code << _endline; - - _indentationLevel++; - } - - virtual void printElse(Node& node) { - /** - * the first argument is the if start node, the following arguments - * are assignments in the previous if branch - */ - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::Else, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 1, "Invalid number of arguments for an 'else' operation"); - - checkEquationEnvEnd(); - _indentationLevel--; - - // close previous environment - CGOpCode nType = node.getArguments()[0].getOperation()->getOperationType(); - if (nType == CGOpCode::StartIf) { - _code << _ifEnd << _endline; - } else if (nType == CGOpCode::ElseIf) { - _code << _elseIfEnd << _endline; - } - - // start else - _code << _elseStart << _endline; - - _indentationLevel++; - } - - virtual void printEndIf(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::EndIf, "Invalid node type for an 'end if' operation"); - - _indentationLevel--; - - // close previous environment - CGOpCode nType = node.getArguments()[0].getOperation()->getOperationType(); - if (nType == CGOpCode::StartIf) { - _code << _ifEnd << _endline; - } else if (nType == CGOpCode::ElseIf) { - _code << _elseIfEnd << _endline; - } else { - assert(nType == CGOpCode::Else); - _code << _elseEnd << _endline; - } - } - - virtual void printCondResult(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::CondResult, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 2, "Invalid number of arguments for an assignment inside an if/else operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an an assignment inside an if/else operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[1].getOperation() != nullptr, "Invalid argument for an an assignment inside an if/else operation"); - - // just follow the argument - Node& nodeArg = *node.getArguments()[1].getOperation(); - printAssignment(nodeArg); - } - - virtual void printUserCustom(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::UserCustom, "Invalid node type"); - - throw CGException("Unable to generate Latex for user custom operation nodes."); - } - - inline bool isDependent(const Node& arg) const { - if (arg.getOperationType() == CGOpCode::LoopIndexedDep) { - return true; - } - size_t id = getVariableID(arg); - return id > _independentSize && id < _minTemporaryVarID; - } - - virtual void printParameter(const Base& value) { - // make sure all digits of floating point values are printed - std::ostringstream os; - os << std::setprecision(_parameterPrecision) << value; - - std::string number = os.str(); - size_t pos = number.find('e'); - if (pos != std::string::npos) { - std::string n = " \\times 10^{"; - number.replace(pos, 1, n); - pos += n.size(); - if (number[pos] == '-' || number[pos] == '+') - pos++; - while (number[pos] == '0') - number.replace(pos, 1, ""); // remove zeros - - number += "}"; - } - _code << number; - - } - - virtual const std::string& getComparison(enum CGOpCode op) const { - switch (op) { - case CGOpCode::ComLt: - return _COMP_OP_LT; - - case CGOpCode::ComLe: - return _COMP_OP_LE; - - case CGOpCode::ComEq: - return _COMP_OP_EQ; - - case CGOpCode::ComGe: - return _COMP_OP_GE; - - case CGOpCode::ComGt: - return _COMP_OP_GT; - - case CGOpCode::ComNe: - return _COMP_OP_NE; - - default: - CPPAD_ASSERT_UNKNOWN(0); - } - throw CGException("Invalid comparison operator code"); // should never get here - } - - inline const std::string& getPrintfBaseFormat() { - static const std::string format; // empty string - return format; - } - - static bool isFunction(enum CGOpCode op) { - return isUnaryFunction(op) || op == CGOpCode::Pow; - } - - static bool isUnaryFunction(enum CGOpCode op) { - switch (op) { - case CGOpCode::Abs: - case CGOpCode::Acos: - case CGOpCode::Asin: - case CGOpCode::Atan: - case CGOpCode::Cosh: - case CGOpCode::Cos: - case CGOpCode::Exp: - case CGOpCode::Log: - case CGOpCode::Sign: - case CGOpCode::Sinh: - case CGOpCode::Sin: - case CGOpCode::Sqrt: - case CGOpCode::Tanh: - case CGOpCode::Tan: - return true; - default: - return false; - } - } - - static bool isCondAssign(enum CGOpCode op) { - switch (op) { - case CGOpCode::ComLt: - case CGOpCode::ComLe: - case CGOpCode::ComEq: - case CGOpCode::ComGe: - case CGOpCode::ComGt: - case CGOpCode::ComNe: - return true; - default: - return false; - } - } -}; - -template -const std::string LanguageLatex::_COMP_OP_LT = "<"; -template -const std::string LanguageLatex::_COMP_OP_LE = "\\le"; -template -const std::string LanguageLatex::_COMP_OP_EQ = "=="; -template -const std::string LanguageLatex::_COMP_OP_GE = "\\ge"; -template -const std::string LanguageLatex::_COMP_OP_GT = ">"; -template -const std::string LanguageLatex::_COMP_OP_NE = "\\ne"; - -template -const std::string LanguageLatex::_C_STATIC_INDEX_ARRAY = "index"; - -template -const std::string LanguageLatex::_C_SPARSE_INDEX_ARRAY = "idx"; - -template -const std::string LanguageLatex::_ATOMIC_TX = "atx"; - -template -const std::string LanguageLatex::_ATOMIC_TY = "aty"; - -template -const std::string LanguageLatex::_ATOMIC_PX = "apx"; - -template -const std::string LanguageLatex::_ATOMIC_PY = "apy"; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/latex/language_latex_arrays.hpp b/ct_core/include/ct/external/cppad/cg/lang/latex/language_latex_arrays.hpp deleted file mode 100644 index 948967962..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/latex/language_latex_arrays.hpp +++ /dev/null @@ -1,370 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_LATEX_ARRAYS_INCLUDED -#define CPPAD_CG_LANGUAGE_LATEX_ARRAYS_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -void LanguageLatex::printArrayCreationOp(OperationNode& array) { - CPPADCG_ASSERT_KNOWN(array.getArguments().size() > 0, "Invalid number of arguments for array creation operation"); - const size_t id = getVariableID(array); - const std::vector >& args = array.getArguments(); - const size_t argSize = args.size(); - - size_t startPos = id - 1; - - bool firstElement = true; - for (size_t i = 0; i < argSize; i++) { - bool newValue = !isSameArgument(args[i], _tmpArrayValues[startPos + i]); - - if (newValue) { - if (firstElement) { - _code << _startAlgLine << _startEq - << auxArrayName_ << _assignStr << _nameGen->generateTemporaryArray(array, getVariableID(array)) - << _endEq << _endAlgLine - << " % size: " << args.size() << _endline; - firstElement = false; - } - - // try to use a loop for element assignment - size_t newI = printArrayCreationUsingLoop(startPos, array, i, _tmpArrayValues); - - // print elements not assign in a loop - if (newI == i) { - // individual element assignment - _code << _startAlgLine << _startEq - << auxArrayName_ << "[" << i << "]" << _assignStr; - print(args[i]); - _code << _endEq << _endAlgLine << _endline; - - _tmpArrayValues[startPos + i] = &args[i]; - - } else { - i = newI - 1; - } - } - } -} - -template -void LanguageLatex::printSparseArrayCreationOp(OperationNode& array) { - const std::vector& info = array.getInfo(); - CPPADCG_ASSERT_KNOWN(info.size() > 0, "Invalid number of information elements for sparse array creation operation"); - - const std::vector >& args = array.getArguments(); - const size_t argSize = args.size(); - - CPPADCG_ASSERT_KNOWN(info.size() == argSize + 1, "Invalid number of arguments for sparse array creation operation"); - - if (argSize == 0) - return; // empty array - - const size_t id = getVariableID(array); - size_t startPos = id - 1; - - bool firstElement = true; - for (size_t i = 0; i < argSize; i++) { - bool newValue = !isSameArgument(args[i], _tmpSparseArrayValues[startPos + i]); - - if (newValue) { - if (firstElement) { - _code << _startAlgLine << _startEq - << auxArrayName_ << _assignStr << _nameGen->generateTemporarySparseArray(array, getVariableID(array)) - << _endEq << _endAlgLine - << " % nnz: " << args.size() << " size:" << info[0] << _endline; - firstElement = false; - } - - // try to use a loop for element assignment - size_t newI = printArrayCreationUsingLoop(startPos, array, i, _tmpSparseArrayValues); - - // print element values not assign in a loop - if (newI == i) { - // individual element assignment - _code << _startAlgLine << _startEq - << auxArrayName_ << "[" << i << "]" << _assignStr; - print(args[i]); - _code << _endEq; - _code << ", "; - // print indexes (location of values) - _code << _startEq - << _C_SPARSE_INDEX_ARRAY << "["; - if (startPos != 0) _code << startPos << "+"; - _code << i << "]" << _assignStr << info[i + 1] - << _endEq << _endAlgLine << _endline; - - _tmpSparseArrayValues[startPos + i] = &args[i]; - - } else { - // print indexes (location of values) - for (size_t j = i; j < newI; j++) { - _code << _startAlgLine << _startEq - << _C_SPARSE_INDEX_ARRAY << "["; - if (startPos != 0) _code << startPos << "+"; - _code << j << "]" << _assignStr << info[j + 1] - << _endEq << _endAlgLine << _endline; - } - - i = newI - 1; - } - - - } else { - // print indexes (location of values) - _code << _startAlgLine << _startEq - << _C_SPARSE_INDEX_ARRAY << "["; - if (startPos != 0) _code << startPos << "+"; - _code << i << "]" << _assignStr << info[i + 1] - << _endEq << _endAlgLine << _endline; - } - - } -} - -template -inline size_t LanguageLatex::printArrayCreationUsingLoop(size_t startPos, - OperationNode& array, - size_t starti, - std::vector*>& tmpArrayValues) { - const std::vector >& args = array.getArguments(); - const size_t argSize = args.size(); - size_t i = starti + 1; - - std::ostringstream arrayAssign; - - const Argument& ref = args[starti]; - if (ref.getOperation() != nullptr) { - // - const OperationNode& refOp = *ref.getOperation(); - if (refOp.getOperationType() == CGOpCode::Inv) { - /** - * from independents array - */ - for (; i < argSize; i++) { - if (isSameArgument(args[i], tmpArrayValues[startPos + i])) - break; // no assignment needed - - if (args[i].getOperation() == nullptr || - args[i].getOperation()->getOperationType() != CGOpCode::Inv || - !_nameGen->isConsecutiveInIndepArray(*args[i - 1].getOperation(), getVariableID(*args[i - 1].getOperation()), - *args[i].getOperation(), getVariableID(*args[i].getOperation()))) { - break; - } - } - - if (i - starti < 3) - return starti; - - // use loop - const std::string& indep = _nameGen->getIndependentArrayName(refOp, getVariableID(refOp)); - size_t start = _nameGen->getIndependentArrayIndex(refOp, getVariableID(refOp)); - long offset = long(start) - starti; - if (offset == 0) - arrayAssign << indep << "[i]"; - else - arrayAssign << indep << "[" << offset << " + i]"; - - } else if (refOp.getOperationType() == CGOpCode::LoopIndexedIndep) { - /** - * from independents array in a loop - */ - size_t pos = refOp.getInfo()[1]; - IndexPattern* refIp = _info->loopIndependentIndexPatterns[pos]; - if (refIp->getType() != IndexPatternType::Linear) { - return starti; // cannot determine consecutive elements - } - - LinearIndexPattern* refLIp = static_cast (refIp); - - for (; i < argSize; i++) { - if (isSameArgument(args[i], tmpArrayValues[startPos + i])) - break; // no assignment needed - - if (args[i].getOperation() == nullptr || - args[i].getOperation()->getOperationType() != CGOpCode::LoopIndexedIndep) { - break; // not an independent index pattern - } - - if (!_nameGen->isInSameIndependentArray(refOp, getVariableID(refOp), - *args[i].getOperation(), getVariableID(*args[i].getOperation()))) - break; - - pos = args[i].getOperation()->getInfo()[1]; - const IndexPattern* ip = _info->loopIndependentIndexPatterns[pos]; - if (ip->getType() != IndexPatternType::Linear) { - break; // different pattern type - } - const LinearIndexPattern* lIp = static_cast (ip); - if (refLIp->getLinearSlopeDx() != lIp->getLinearSlopeDx() || - refLIp->getLinearSlopeDy() != lIp->getLinearSlopeDy() || - refLIp->getXOffset() != lIp->getXOffset() || - refLIp->getLinearConstantTerm() - long(starti) != lIp->getLinearConstantTerm() - long(i)) { - break; - } - } - - if (i - starti < 3) - return starti; - - LinearIndexPattern* lip2 = new LinearIndexPattern(*refLIp); - lip2->setLinearConstantTerm(lip2->getLinearConstantTerm() - starti); - Plane2DIndexPattern p2dip(lip2, - new LinearIndexPattern(0, 1, 1, 0)); - - std::unique_ptr> op2(OperationNode::makeTemporaryNode(CGOpCode::LoopIndexedIndep, refOp.getInfo(), refOp.getArguments())); - op2->getInfo()[1] = std::numeric_limits::max(); // just to be safe (this would be the index pattern id in the handler) - op2->getArguments().push_back(_info->auxIterationIndexOp); - - arrayAssign << _nameGen->generateIndexedIndependent(*op2, 0, p2dip); - - } else { - // no loop used - return starti; - } - } else { - /** - * constant value? - */ - const Base& value = *args[starti].getParameter(); - for (; i < argSize; i++) { - if (args[i].getParameter() == nullptr || *args[i].getParameter() != value) { - break; // not the same constant value - } - - const Argument* oldArg = tmpArrayValues[startPos + i]; - if (oldArg != nullptr && oldArg->getParameter() != nullptr && *oldArg->getParameter() == value) { - break; // values are the same (no need to redefine) - } - } - - if (i - starti < 3) - return starti; - - arrayAssign << value; - } - - /** - * print the loop - */ - _code << _forStart << "{$i " << _assignStr << starti << "$ to $" << (i - 1) << "$}" << _endline; - _indentationLevel++; - _code << _startAlgLine << _startEq - << auxArrayName_ << "[i]" << _assignStr << arrayAssign.str() - << _endEq << _endAlgLine << _endline; - _indentationLevel--; - _code << _forEnd << _endline; - - /** - * update values in the global temporary array - */ - for (size_t ii = starti; ii < i; ii++) { - tmpArrayValues[startPos + ii] = &args[ii]; - } - - return i; -} - -template -inline std::string LanguageLatex::getTempArrayName(const OperationNode& op) { - if (op.getOperationType() == CGOpCode::ArrayCreation) - return _nameGen->generateTemporaryArray(op); - else - return _nameGen->generateTemporarySparseArray(op); -} - -template -void LanguageLatex::printArrayElementOp(OperationNode& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for array element operation"); - CPPADCG_ASSERT_KNOWN(op.getArguments()[0].getOperation() != nullptr, "Invalid argument for array element operation"); - CPPADCG_ASSERT_KNOWN(op.getInfo().size() == 1, "Invalid number of information indexes for array element operation"); - - OperationNode& arrayOp = *op.getArguments()[0].getOperation(); - std::string arrayName; - if (arrayOp.getOperationType() == CGOpCode::ArrayCreation) - arrayName = _nameGen->generateTemporaryArray(arrayOp, getVariableID(arrayOp)); - else - arrayName = _nameGen->generateTemporarySparseArray(arrayOp, getVariableID(arrayOp)); - - _code << "(" << arrayName << ")[" << op.getInfo()[0] << "]"; -} - -template -inline void LanguageLatex::printArrayStructInit(const std::string& dataArrayName, - size_t pos, - const std::vector*>& arrays, - size_t k) { - _ss.str(""); - _ss << dataArrayName << "[" << pos << "]"; - printArrayStructInit(_ss.str(), *arrays[k]); -} - -template -inline void LanguageLatex::printArrayStructInit(const std::string& dataArrayName, - OperationNode& array) { - /** - * TODO: finish this - */ - const std::string& aName = createVariableName(array); - - if (array.getOperationType() == CGOpCode::ArrayCreation) { - // dense array - size_t size = array.getArguments().size(); - if (size > 0) - _code << dataArrayName << ".data = " << aName << "; "; - else - _code << dataArrayName << ".data = NULL; "; - _code << dataArrayName << ".size = " << size << "; " - << dataArrayName << ".sparse = " << false << ";"; - } else { - // sparse array - CPPADCG_ASSERT_KNOWN(array.getOperationType() == CGOpCode::SparseArrayCreation, "Invalid node type"); - size_t nnz = array.getArguments().size(); - if (nnz > 0) - _code << dataArrayName << ".data = " << aName << "; "; - else - _code << dataArrayName << ".data = NULL; "; - _code << dataArrayName << ".size = " << array.getInfo()[0] << "; " - << dataArrayName << ".sparse = " << true << "; " - << dataArrayName << ".nnz = " << nnz << "; "; - if (nnz > 0) { - size_t id = getVariableID(array); - _code << dataArrayName << ".idx = &(" << _C_SPARSE_INDEX_ARRAY << "[" << (id - 1) << "]);"; - } - } - _code << _endline; -} - -template -inline void LanguageLatex::markArrayChanged(OperationNode& ty) { - size_t id = getVariableID(ty); - size_t tySize = ty.getArguments().size(); - - if (ty.getOperationType() == CGOpCode::ArrayCreation) { - for (size_t i = 0; i < tySize; i++) { - _tmpArrayValues[id - 1 + i] = nullptr; - } - } else { - for (size_t i = 0; i < tySize; i++) { - _tmpSparseArrayValues[id - 1 + i] = nullptr; - } - } -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/latex/language_latex_index_patterns.hpp b/ct_core/include/ct/external/cppad/cg/lang/latex/language_latex_index_patterns.hpp deleted file mode 100644 index 3292df72a..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/latex/language_latex_index_patterns.hpp +++ /dev/null @@ -1,277 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_LATEX_INDEX_PATTERNS_INCLUDED -#define CPPAD_CG_LANGUAGE_LATEX_INDEX_PATTERNS_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -inline void LanguageLatex::generateNames4RandomIndexPatterns(const std::set& randomPatterns) { - std::ostringstream os; - - std::set usedNames; - - // save existing names so that they are not to overridden - // (independent variable names might have already used them) - for (RandomIndexPattern* ip : randomPatterns) { - if (!ip->getName().empty()) { - usedNames.insert(ip->getName()); - } - } - - // create new names for the index pattern arrays without a name - size_t c = 0; - for (RandomIndexPattern* ip : randomPatterns) { - if (ip->getName().empty()) { - // new name required - std::string name; - do { - os << _C_STATIC_INDEX_ARRAY << c; - name = os.str(); - os.str(""); - c++; - } while (usedNames.find(name) != usedNames.end()); - - ip->setName(name); - } - } - -} - -template -inline void LanguageLatex::printRandomIndexPatternDeclaration(std::ostringstream& os, - const std::string& indentation, - const std::set& randomPatterns) { - for (RandomIndexPattern* ip : randomPatterns) { - if (ip->getType() == IndexPatternType::Random1D) { - /** - * 1D - */ - Random1DIndexPattern* ip1 = static_cast (ip); - const std::map& x2y = ip1->getValues(); - - std::vector y(x2y.rbegin()->first + 1); - for (const std::pair& p : x2y) - y[p.first] = p.second; - - os << indentation; - printStaticIndexArray(os, ip->getName(), y); - } else { - CPPADCG_ASSERT_UNKNOWN(ip->getType() == IndexPatternType::Random2D); - /** - * 2D - */ - Random2DIndexPattern* ip2 = static_cast (ip); - os << indentation; - printStaticIndexMatrix(os, ip->getName(), ip2->getValues()); - } - } -} - -template -void LanguageLatex::printStaticIndexArray(std::ostringstream& os, - const std::string& name, - const std::vector& values) { - /** - * TODO - */ - os << name << " = \\{["; - if (!values.empty()) { - os << values[0]; - for (size_t i = 1; i < values.size(); i++) { - os << " " << values[i]; - } - } - os << "]\\}" << _endEq << " % size: " << values.size() << _endline; -} - -template -void LanguageLatex::printStaticIndexMatrix(std::ostringstream& os, - const std::string& name, - const std::map >& values) { - /** - * TODO - */ - size_t m = 0; - size_t n = 0; - - std::map >::const_iterator it; - std::map::const_iterator ity2z; - - if (!values.empty()) { - m = values.rbegin()->first + 1; - - for (it = values.begin(); it != values.end(); ++it) { - if (!it->second.empty()) - n = std::max(n, it->second.rbegin()->first + 1); - } - } - - os << name << " = \\{"; - size_t x = 0; - for (it = values.begin(); it != values.end(); ++it) { - if (it->first != x) { - while (it->first != x) { - os << "{},"; - x++; - } - } - - os << "{"; - - size_t y = 0; - for (ity2z = it->second.begin(); ity2z != it->second.end(); ++ity2z) { - if (ity2z->first != y) { - while (ity2z->first != y) { - os << "0,"; - y++; - } - } - - os << ity2z->second; - if (ity2z->first != it->second.rbegin()->first) os << ","; - - y++; - } - - os << "}"; - if (it->first != values.rbegin()->first) os << ","; - - x++; - } - os << "\\}" << _endEq << "% size: " << m << " x " << n << _endline; -} - -template -inline std::string LanguageLatex::indexPattern2String(const IndexPattern& ip, - const OperationNode& index) { - return indexPattern2String(ip,{&index}); -} - -template -inline std::string LanguageLatex::indexPattern2String(const IndexPattern& ip, - const std::vector*>& indexes) { - std::stringstream ss; - switch (ip.getType()) { - case IndexPatternType::Linear: // y = x * a + b - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 1, "Invalid number of indexes"); - const LinearIndexPattern& lip = static_cast (ip); - return linearIndexPattern2String(lip, *indexes[0]); - } - case IndexPatternType::Sectioned: - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 1, "Invalid number of indexes"); - const SectionedIndexPattern* lip = static_cast (&ip); - const std::map& sections = lip->getLinearSections(); - size_t sSize = sections.size(); - CPPADCG_ASSERT_UNKNOWN(sSize > 1); - - std::map::const_iterator its = sections.begin(); - for (size_t s = 0; s < sSize - 1; s++) { - const IndexPattern* lp = its->second; - ++its; - size_t xStart = its->first; - - ss << "(" << (*indexes[0]->getName()) << "<" << xStart << ")? " - << indexPattern2String(*lp, *indexes[0]) << ": "; - } - ss << indexPattern2String(*its->second, *indexes[0]); - - return ss.str(); - } - - case IndexPatternType::Plane2D: // y = f(x) + f(z) - { - CPPADCG_ASSERT_KNOWN(indexes.size() >= 1, "Invalid number of indexes"); - std::string indexExpr; - const Plane2DIndexPattern& pip = static_cast (ip); - bool useParens = pip.getPattern1() != nullptr && pip.getPattern2() != nullptr; - - if (useParens) indexExpr += "("; - - if (pip.getPattern1() != nullptr) - indexExpr += indexPattern2String(*pip.getPattern1(), *indexes[0]); - - if (useParens) indexExpr += ") + ("; - - if (pip.getPattern2() != nullptr) - indexExpr += indexPattern2String(*pip.getPattern2(), *indexes.back()); - - if (useParens) indexExpr += ")"; - - return indexExpr; - } - case IndexPatternType::Random1D: - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 1, "Invalid number of indexes"); - const Random1DIndexPattern& rip = static_cast (ip); - CPPADCG_ASSERT_KNOWN(!rip.getName().empty(), "Invalid name for array"); - return rip.getName() + "[" + (*indexes[0]->getName()) + "]"; - } - case IndexPatternType::Random2D: - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 2, "Invalid number of indexes"); - const Random2DIndexPattern& rip = static_cast (ip); - CPPADCG_ASSERT_KNOWN(!rip.getName().empty(), "Invalid name for array"); - return rip.getName() + "[" + (*indexes[0]->getName()) + "][" + (*indexes[1]->getName()) + "]"; - } - default: - CPPADCG_ASSERT_UNKNOWN(false); // should never reach this - return ""; - } -} - -template -inline std::string LanguageLatex::linearIndexPattern2String(const LinearIndexPattern& lip, - const OperationNode& index) { - long dy = lip.getLinearSlopeDy(); - long dx = lip.getLinearSlopeDx(); - long b = lip.getLinearConstantTerm(); - long xOffset = lip.getXOffset(); - - std::stringstream ss; - if (dy != 0) { - if (xOffset != 0) { - ss << "("; - } - ss << (*index.getName()); - if (xOffset != 0) { - ss << " - " << xOffset << ")"; - } - - if (dx != 1) { - ss << " / " << dx; - } - if (dy != 1) { - ss << " * " << dy; - } - } else if (b == 0) { - ss << "0"; // when dy == 0 and b == 0 - } - - if (b != 0) { - if (dy != 0) - ss << " + "; - ss << b; - } - return ss.str(); -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/latex/latex.hpp b/ct_core/include/ct/external/cppad/cg/lang/latex/latex.hpp deleted file mode 100644 index 4ec942dff..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/latex/latex.hpp +++ /dev/null @@ -1,28 +0,0 @@ -#ifndef CPPAD_CG_LATEX_INCLUDED -#define CPPAD_CG_LATEX_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -// --------------------------------------------------------------------------- -// latex source code generation -#include -#include -#include -#include -//#include -//#include -#include - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/mathml/lang_mathml_custom_var_name_gen.hpp b/ct_core/include/ct/external/cppad/cg/lang/mathml/lang_mathml_custom_var_name_gen.hpp deleted file mode 100644 index 2491c687e..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/mathml/lang_mathml_custom_var_name_gen.hpp +++ /dev/null @@ -1,101 +0,0 @@ -#ifndef CPPAD_CG_LANG_MATHML_CUSTOM_VAR_NAME_GEN_INCLUDED -#define CPPAD_CG_LANG_MATHML_CUSTOM_VAR_NAME_GEN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2015 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Creates variables names for the source code using a list of provided - * custom names. - * - * @author Joao Leal - */ -template -class LangMathMLCustomVariableNameGenerator : public LangMathMLDefaultVariableNameGenerator { -protected: - typedef LangMathMLDefaultVariableNameGenerator Super; - // the custom names for the dependent variables - const std::vector depNames_; - // the custom names for the independent variables - const std::vector indepNames_; -public: - - LangMathMLCustomVariableNameGenerator(const std::vector& depNames, - const std::vector& indepNames, - const std::string& depName = "y", - const std::string& indepName = "x", - const std::string& tmpName = "v", - const std::string& tmpArrayName = "a", - const std::string& tmpSparseArrayName = "s") : - LangMathMLDefaultVariableNameGenerator(depName, indepName, tmpName, tmpArrayName, tmpSparseArrayName), - depNames_(depNames), - indepNames_(indepNames) { - } - - virtual std::string generateDependent(size_t index) override { - if (index < depNames_.size() && !depNames_[index].empty()) { - return depNames_[index]; - } else { - return Super::generateDependent(index); - } - } - - virtual std::string generateIndependent(const OperationNode& independent, - size_t id) override { - size_t index = id - 1; - if (index < indepNames_.size() && !indepNames_[index].empty()) { - return indepNames_[index]; - } else { - return Super::generateIndependent(independent, id); - } - } - - virtual bool isConsecutiveInIndepArray(const OperationNode& indepFirst, - size_t idFirst, - const OperationNode& indepSecond, - size_t idSecond) override { - size_t index1 = idFirst - 1; - size_t index2 = idSecond - 1; - - if ((index1 > indepNames_.size() || indepNames_[index1].empty()) && - (index2 > indepNames_.size() || indepNames_[index2].empty())) { - return index1 + 1 == index2; - } else { - return false; // individual names used (not elements of arrays) - } - } - - virtual bool isInSameIndependentArray(const OperationNode& indep1, - size_t id1, - const OperationNode& indep2, - size_t id2) override { - size_t index1 = id1 - 1; - size_t index2 = id2 - 1; - - return (index1 > indepNames_.size() || indepNames_[index1].empty()) && - (index2 > indepNames_.size() || indepNames_[index2].empty()); - } - - inline virtual ~LangMathMLCustomVariableNameGenerator() { - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/mathml/lang_mathml_default_var_name_gen.hpp b/ct_core/include/ct/external/cppad/cg/lang/mathml/lang_mathml_default_var_name_gen.hpp deleted file mode 100644 index 34320693b..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/mathml/lang_mathml_default_var_name_gen.hpp +++ /dev/null @@ -1,291 +0,0 @@ -#ifndef CPPAD_CG_LANG_MATHML_DEFAULT_VAR_NAME_GEN_INCLUDED -#define CPPAD_CG_LANG_MATHML_DEFAULT_VAR_NAME_GEN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2015 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Creates variables names for MathML source code. - * - * @author Joao Leal - */ -template -class LangMathMLDefaultVariableNameGenerator : public VariableNameGenerator { -protected: - // auxiliary string stream - std::stringstream _ss; - // array name of the dependent variables - std::string _depName; - // array name of the independent variables - std::string _indepName; - // array name of the temporary variables - std::string _tmpName; - // array name of the temporary array variables - std::string _tmpArrayName; - // sparse array name of the temporary array variables - std::string _tmpSparseArrayName; - // the lowest variable ID used for the temporary variables - size_t _minTemporaryID; - // the highest variable ID used for the temporary variables - size_t _maxTemporaryID; - // the highest ID used for the temporary array variables - size_t _maxTemporaryArrayID; - // the highest ID used for the temporary sparse array variables - size_t _maxTemporarySparseArrayID; -public: - - inline LangMathMLDefaultVariableNameGenerator(const std::string& depName = "y", - const std::string& indepName = "x", - const std::string& tmpName = "v", - const std::string& tmpArrayName = "a", - const std::string& tmpSparseArrayName = "s") : - _depName(depName), - _indepName(indepName), - _tmpName(tmpName), - _tmpArrayName(tmpArrayName), - _tmpSparseArrayName(tmpSparseArrayName), - _minTemporaryID(0), // not really required (but it avoids warnings) - _maxTemporaryID(0), // not really required (but it avoids warnings) - _maxTemporaryArrayID(0), // not really required (but it avoids warnings) - _maxTemporarySparseArrayID(0) { // not really required (but it avoids warnings) - - this->_independent.push_back(FuncArgument(_indepName)); - this->_dependent.push_back(FuncArgument(_depName)); - this->_temporary.push_back(FuncArgument(_tmpName)); - this->_temporary.push_back(FuncArgument(_tmpArrayName)); - this->_temporary.push_back(FuncArgument(_tmpSparseArrayName)); - } - - inline virtual size_t getMinTemporaryVariableID() const override { - return _minTemporaryID; - } - - inline virtual size_t getMaxTemporaryVariableID() const override { - return _maxTemporaryID; - } - - inline virtual size_t getMaxTemporaryArrayVariableID() const override { - return _maxTemporaryArrayID; - } - - virtual size_t getMaxTemporarySparseArrayVariableID() const override { - return _maxTemporarySparseArrayID; - } - - inline virtual std::string generateDependent(size_t index) override { - _ss.clear(); - _ss.str(""); - - _ss << "" - "" << _depName << "" - "" << index << "" - ""; - - return _ss.str(); - } - - inline virtual std::string generateIndependent(const OperationNode& independent, - size_t id) override { - _ss.clear(); - _ss.str(""); - - _ss << "" - "" << _indepName << "" - "" << (id - 1) << "" - ""; - - return _ss.str(); - } - - inline virtual std::string generateTemporary(const OperationNode& variable, - size_t id) override { - _ss.clear(); - _ss.str(""); - - if (this->_temporary[0].array) { - _ss << "" - "" << _tmpName << "" - "" << (id - this->_minTemporaryID) << "" - ""; - } else { - _ss << "" - "" << _tmpName << "" - "" << id << "" - ""; - } - - return _ss.str(); - } - - virtual std::string generateTemporaryArray(const OperationNode& variable, - size_t id) override { - _ss.clear(); - _ss.str(""); - - CPPADCG_ASSERT_UNKNOWN(variable.getOperationType() == CGOpCode::ArrayCreation); - - _ss << "" << _tmpArrayName << "" - "" - "" - "" << id - 1 << "" - ":"///////////////////////////////////////// TODO - "" - ""; - - return _ss.str(); - } - - virtual std::string generateTemporarySparseArray(const OperationNode& variable, - size_t id) override { - _ss.clear(); - _ss.str(""); - - CPPADCG_ASSERT_UNKNOWN(variable.getOperationType() == CGOpCode::SparseArrayCreation); - - _ss << "" << _tmpSparseArrayName << "" - "" - "" - "" << id - 1 << "" - ":"///////////////////////////////////////// TODO - "" - ""; - - return _ss.str(); - } - - virtual std::string generateIndexedDependent(const OperationNode& var, - size_t id, - const IndexPattern& ip) override { - CPPADCG_ASSERT_KNOWN(var.getOperationType() == CGOpCode::LoopIndexedDep, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(!var.getArguments().empty(), "Invalid number of arguments"); - - _ss.clear(); - _ss.str(""); - - _ss << "" - "" << _depName << ""; - LanguageMathML::indexPattern2String(_ss, ip, getIndexes(var, 1)); - _ss << ""; - - return _ss.str(); - } - - virtual std::string generateIndexedIndependent(const OperationNode& independent, - size_t id, - const IndexPattern& ip) override { - CPPADCG_ASSERT_KNOWN(independent.getOperationType() == CGOpCode::LoopIndexedIndep, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(independent.getArguments().size() > 0, "Invalid number of arguments"); - - _ss.clear(); - _ss.str(""); - - - _ss << "" - "" << _indepName << ""; - LanguageMathML::indexPattern2String(_ss, ip, getIndexes(independent)); - _ss << ""; - - return _ss.str(); - } - - inline virtual void setTemporaryVariableID(size_t minTempID, - size_t maxTempID, - size_t maxTempArrayID, - size_t maxTempSparseArrayID) override { - _minTemporaryID = minTempID; - _maxTemporaryID = maxTempID; - _maxTemporaryArrayID = maxTempArrayID; - _maxTemporarySparseArrayID = maxTempSparseArrayID; - - // if - // _minTemporaryID == _maxTemporaryID + 1 - // then no temporary variables are being used - CPPADCG_ASSERT_UNKNOWN(_minTemporaryID <= _maxTemporaryID + 1); - } - - virtual const std::string& getIndependentArrayName(const OperationNode& indep, - size_t id) override { - return _indepName; - } - - virtual size_t getIndependentArrayIndex(const OperationNode& indep, - size_t id) override { - return id - 1; - } - - virtual bool isConsecutiveInIndepArray(const OperationNode& indepFirst, - size_t idFirst, - const OperationNode& indepSecond, - size_t idSecond) override { - return idFirst + 1 == idSecond; - } - - virtual bool isInSameIndependentArray(const OperationNode& indep1, - size_t id1, - const OperationNode& indep2, - size_t id2) override { - return true; - } - - virtual const std::string& getTemporaryVarArrayName(const OperationNode& var, - size_t id) override { - return _tmpName; - } - - virtual size_t getTemporaryVarArrayIndex(const OperationNode& var, - size_t id) override { - return id - this->_minTemporaryID; - } - - virtual bool isConsecutiveInTemporaryVarArray(const OperationNode& varFirst, - size_t idFirst, - const OperationNode& varSecond, - size_t idSecond) override { - return idFirst + 1 == idSecond; - } - - virtual bool isInSameTemporaryVarArray(const OperationNode& var1, - size_t id1, - const OperationNode& var2, - size_t id2) override { - return true; - } - - inline virtual ~LangMathMLDefaultVariableNameGenerator() { - } -protected: - - static inline std::vector*> getIndexes(const OperationNode& var, - size_t offset = 0) { - const std::vector >& args = var.getArguments(); - std::vector*> indexes(args.size() - offset); - - for (size_t a = offset; a < args.size(); a++) { - CPPADCG_ASSERT_KNOWN(args[a].getOperation() != nullptr, "Invalid argument"); - CPPADCG_ASSERT_KNOWN(args[a].getOperation()->getOperationType() == CGOpCode::Index, "Invalid argument"); - - indexes[a - offset] = &static_cast*> (args[a].getOperation())->getIndex(); - } - - return indexes; - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/mathml/language_mathml.hpp b/ct_core/include/ct/external/cppad/cg/lang/mathml/language_mathml.hpp deleted file mode 100644 index 8070ea1ac..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/mathml/language_mathml.hpp +++ /dev/null @@ -1,2138 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_MATHML_INCLUDED -#define CPPAD_CG_LANGUAGE_MATHML_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2015 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Generates presentation markup using the html and MathML specification. - * - * @author Joao Leal - */ -template -class LanguageMathML : public Language { -public: - typedef OperationNode Node; - typedef Argument Arg; -protected: - static const std::string _C_STATIC_INDEX_ARRAY; - static const std::string _C_SPARSE_INDEX_ARRAY; - static const std::string _ATOMIC_TX; - static const std::string _ATOMIC_TY; - static const std::string _ATOMIC_PX; - static const std::string _ATOMIC_PY; -protected: - // information from the code handler (not owned) - LanguageGenerationData* _info; - // current indentation - size_t _indentationLevel; - // css style - std::string _style; - // javascript source code - std::string _javascript; - // additional markup for the head - std::string _headExtra; - std::string _startEq; - std::string _endEq; - std::string _forStart; - std::string _forEnd; - std::string _forBodyStart; - std::string _forBodyEnd; - std::string _ifStart; - std::string _ifEnd; - std::string _elseIfStart; - std::string _elseIfEnd; - std::string _elseStart; - std::string _elseEnd; - std::string _condBodyStart; - std::string _condBodyEnd; - std::string _assignStr; - std::string _assignAddStr; - // markup for multiplications - std::string _multOpStr; - // markup for multiplications with parameters - std::string _multValOpStr; - // new line characters - std::string _endline; - // output stream for the generated source code - std::ostringstream _code; - // creates the variable names - VariableNameGenerator* _nameGen; - // auxiliary string stream - std::ostringstream _ss; - // - size_t _independentSize; - // - size_t _minTemporaryVarID; - // maps the variable IDs to the their position in the dependent vector - // (some IDs may be the same as the independent variables when dep = indep) - std::map _dependentIDs; - // the dependent variable vector - const ArrayWrapper >* _dependent; - // the temporary variables that may require a declaration - std::map _temporary; - // whether or not to ignore assignment of constant zero values to dependent variables - bool _ignoreZeroDepAssign; - // the name of the file to be created without the extension - std::string _filename; - // the maximum number of assignment (~lines) per local file - size_t _maxAssignmentsPerFile; - // maps filenames to their content - std::map* _sources; - // the values in the temporary array - std::vector _tmpArrayValues; - // the values in the temporary sparse array - std::vector _tmpSparseArrayValues; - // - std::vector*> _currentLoops; - // the maximum precision used to print values - size_t _parameterPrecision; - // whether or not to always enclose the base of a power within parenthesis - bool _powBaseEnclose; - // whether or not to save dependencies among variables in javascript - bool _saveVariableRelations; -private: - std::string auxArrayName_; - std::vector varIds_; - std::vector depConstIds_; - std::vector depIsIndepIds_; -public: - - /** - * Creates a MathML language source code generator - */ - LanguageMathML() : - _info(nullptr), - _indentationLevel(0), - _style(".loop{}\n" - ".loopBody{padding-left: 2em;}\n" - ".condIf{}\n" - ".condElseIf{}\n" - ".condElse{}\n" - ".condBody{padding-left: 2em;}\n" - ".dep{color:#600;}\n" - ".indep{color:#060;}\n" - ".tmp{color:#006;}\n"), - _startEq(""), - _endEq(""), - _forStart("
"), - _forEnd("
"), - _forBodyStart("
"), - _forBodyEnd("
"), - _ifStart("
"), - _ifEnd("
"), - _elseIfStart("
"), - _elseIfEnd("
"), - _elseStart("
"), - _elseEnd("
"), - _condBodyStart("
"), - _condBodyEnd("
"), - _assignStr("="), - _assignAddStr("+="), - _multOpStr(""), - _multValOpStr("×"), - _endline("\n"), - _nameGen(nullptr), - _independentSize(0), // not really required (but it avoids warnings) - _minTemporaryVarID(0), // not really required (but it avoids warnings) - _dependent(nullptr), - _ignoreZeroDepAssign(false), - _filename("algorithm"), - _maxAssignmentsPerFile(0), - _sources(nullptr), - _parameterPrecision(std::numeric_limits::digits10), - _powBaseEnclose(false), - _saveVariableRelations(false) { - } - - inline virtual ~LanguageMathML() { - } - - inline const std::string& getAssignMarkup() const { - return _assignStr; - } - - inline void setAssignMarkup(const std::string& assign) { - _assignStr = assign; - } - - inline const std::string& getAddAssignMarkup() const { - return _assignAddStr; - } - - inline void setAddAssignMarkup(const std::string& assignAdd) { - _assignAddStr = assignAdd; - } - - /** - * Provides the mathml markup used to define multiplications. - * The default is . - * - * @note Multiplications of constant parameters use a different - * multiplication markup string - */ - inline const std::string& getMultiplicationMarkup() const { - return _multOpStr; - } - - /** - * Defines the mathml markup used for multiplications. - * The default is . - * Other common alternatives are "" and "×". - * - * @note Multiplications of constant parameters use a different - * multiplication markup string - */ - inline void setMultiplicationMarkup(const std::string& multOpStr) { - _multOpStr = multOpStr; - } - - /** - * Provides the mathml markup used for multiplications of constant - * parameters. - * The default is ×. - */ - inline const std::string& getMultiplicationConstParMarkup() const { - return _multValOpStr; - } - - /** - * Defines the mathml markup used for multiplications of constant - * parameters. - * The default is ×. - * Another common alternative is "". - * Please take into account that numbers too close together are difficult - * to distinguish. - */ - inline void setMultiplicationConstParMarkup(const std::string& multValOpStr) { - _multValOpStr = multValOpStr; - } - - inline bool isIgnoreZeroDepAssign() const { - return _ignoreZeroDepAssign; - } - - inline void setIgnoreZeroDepAssign(bool ignore) { - _ignoreZeroDepAssign = ignore; - } - - void setFilename(const std::string& name) { - _filename = name; - } - - /** - * Defines the CSS style to be added to head section of the html document. - * - * @param style the content of the CSS - */ - void setStyle(const std::string& style) { - _style = style; - } - - const std::string& getStyle() const { - return _style; - } - - /** - * Defines Javascript source code to be added to head section of the html document. - * - * @param javascript the Javascript source code - */ - void setJavascript(const std::string& javascript) { - _javascript = javascript; - } - - const std::string& getJavascript() const { - return _javascript; - } - - /** - * Defines additional markup to be added to head section of the html document. - * - * @param headExtra html markup to be added to the head section - */ - void setHeadExtraMarkup(const std::string& headExtra) { - _headExtra = headExtra; - } - - const std::string& getHeadExtraMarkup() const { - return _headExtra; - } - - /** - * Defines the surrounding markup for each equation. - * - * @param begin the opening html markup - * @param end the closing html markup - */ - virtual void setEquationMarkup(const std::string& begin, - const std::string& end) { - _startEq = begin; - _endEq = end; - } - - /** - * Provides the markup preceding each equation. - */ - virtual const std::string& getEquationStartMarkup() const { - return _startEq; - } - - /** - * Provides the markup after each equation. - */ - virtual const std::string& getEquationEndMarkup() const { - return _endEq; - } - - /** - * Defines the surrounding markup for each for loop. - * - * @param begin the opening html markup - * @param end the closing html markup - */ - virtual void setForMarkup(const std::string& begin, - const std::string& end) { - _forStart = begin; - _forEnd = end; - } - - /** - * Provides the markup preceding each loop. - */ - virtual const std::string& getForStartMarkup() const { - return _forStart; - } - - /** - * Provides the markup after each loop. - */ - virtual const std::string& getForEndMarkup() const { - return _forEnd; - } - - /** - * Defines the surrounding markup for each If. - * - * @param begin the opening html markup - * @param end the closing html markup - */ - virtual void setIfMarkup(const std::string& begin, - const std::string& end) { - _ifStart = begin; - _ifEnd = end; - } - - /** - * Provides the markup preceding each If. - */ - virtual const std::string& getIfStartMarkup() const { - return _ifStart; - } - - /** - * Provides the markup after each If. - */ - virtual const std::string& getIfEndMarkup() const { - return _ifEnd; - } - - /** - * Defines the surrounding markup for each else if. - * - * @param begin the opening html markup - * @param end the closing html markup - */ - virtual void setElseIfMarkup(const std::string& begin, - const std::string& end) { - _elseIfStart = begin; - _elseIfEnd = end; - } - - /** - * Provides the markup preceding each else if. - */ - virtual const std::string& getElseIfStartMarkup() const { - return _elseIfStart; - } - - /** - * Provides the markup after each else if. - */ - virtual const std::string& getElseIfEndMarkup() const { - return _elseIfEnd; - } - - /** - * Defines the surrounding markup for each else. - * - * @param begin the opening html markup - * @param end the closing html markup - */ - virtual void setElseMarkup(const std::string& begin, - const std::string& end) { - _elseStart = begin; - _elseEnd = end; - } - - /** - * Provides the markup preceding each else. - */ - virtual const std::string& getElseStartMarkup() const { - return _elseStart; - } - - /** - * Provides the markup after each else. - */ - virtual const std::string& getElseEndMarkup() const { - return _elseEnd; - } - - /** - * Provides the maximum precision used to print constant values in the - * generated source code - * - * @return the maximum number of digits - */ - virtual size_t getParameterPrecision() const { - return _parameterPrecision; - } - - /** - * Defines the maximum precision used to print constant values in the - * generated source code - * - * @param p the maximum number of digits - */ - virtual void setParameterPrecision(size_t p) { - _parameterPrecision = p; - } - - /** - * Defines whether or not to always enclose the base of a power within - * parenthesis. - * By default the base is only enclosed in parenthesis if it contains of a - * mathematical expression. - * - * @param enclose true to always enclose the base in parenthesis - */ - virtual void setAlwaysEnclosePowBase(bool enclose) { - _powBaseEnclose = enclose; - } - - /** - * Whether or not to always enclose the base of a power within - * parenthesis. - * - * @return true if the base is always enclosed within parenthesis - */ - virtual bool isAlwaysEnclosePowBase() const { - return _powBaseEnclose; - } - - virtual void setMaxAssignmentsPerFunction(size_t maxAssignmentsPerFunction, - std::map* sources) { - _maxAssignmentsPerFile = maxAssignmentsPerFunction; - _sources = sources; - } - - inline void setSaveVariableRelations(bool save) { - _saveVariableRelations = save; - } - - virtual bool requiresVariableDependencies() const override { - return _saveVariableRelations; - } - - /*************************************************************************** - * STATIC - **************************************************************************/ - static inline void printIndexCondExpr(std::ostringstream& out, - const std::vector& info, - const std::string& index) { - CPPADCG_ASSERT_KNOWN(info.size() > 1 && info.size() % 2 == 0, "Invalid number of information elements for an index condition expression operation"); - - size_t infoSize = info.size(); - for (size_t e = 0; e < infoSize; e += 2) { - if (e > 0) { - out << ""; // or - } - size_t min = info[e]; - size_t max = info[e + 1]; - if (min == max) { - out << "" << index << "==" << min << ""; - } else if (min == 0) { - out << "" << index << "" << max << ""; - } else if (max == std::numeric_limits::max()) { - out << "" << min << "" << index << ""; - } else { - if (infoSize != 2) - out << ""; - - if (max - min == 1) - out << "" << min << "==" << index << "" << index << "==" << max << ""; - else - out << "" << min << "" << index << "" << index << "" << max << ""; - } - } - } - - /*************************************************************************** - * - **************************************************************************/ - - inline void printStaticIndexArray(std::ostringstream& os, - const std::string& name, - const std::vector& values); - - inline void printStaticIndexMatrix(std::ostringstream& os, - const std::string& name, - const std::map >& values); - - /*************************************************************************** - * index patterns - **************************************************************************/ - static inline void generateNames4RandomIndexPatterns(const std::set& randomPatterns); - - inline void printRandomIndexPatternDeclaration(std::ostringstream& os, - const std::string& identation, - const std::set& randomPatterns); - - static void indexPattern2String(std::ostream& os, - const IndexPattern& ip, - const Node& index); - - static void indexPattern2String(std::ostream& os, - const IndexPattern& ip, - const std::vector& indexes); - - static inline void linearIndexPattern2String(std::ostream& os, - const LinearIndexPattern& lip, - const Node& index); - - /*************************************************************************** - * protected - **************************************************************************/ -protected: - - virtual void generateSourceCode(std::ostream& out, - const std::unique_ptr >& info) override { - - const bool multiFile = _maxAssignmentsPerFile > 0 && _sources != nullptr; - - // clean up - _code.str(""); - _ss.str(""); - _indentationLevel = 0; - _temporary.clear(); - auxArrayName_ = ""; - _currentLoops.clear(); - depConstIds_.clear(); - depIsIndepIds_.clear(); - - - // save some info - _info = info.get(); - _independentSize = info->independent.size(); - _dependent = &info->dependent; - _nameGen = &info->nameGen; - _minTemporaryVarID = info->minTemporaryVarID; - const ArrayWrapper >& dependent = info->dependent; - const std::vector& variableOrder = info->variableOrder; - - _tmpArrayValues.resize(_nameGen->getMaxTemporaryArrayVariableID()); - std::fill(_tmpArrayValues.begin(), _tmpArrayValues.end(), nullptr); - _tmpSparseArrayValues.resize(_nameGen->getMaxTemporarySparseArrayVariableID()); - std::fill(_tmpSparseArrayValues.begin(), _tmpSparseArrayValues.end(), nullptr); - - varIds_.resize(_minTemporaryVarID + variableOrder.size()); - std::fill(varIds_.begin(), varIds_.end(), 0); - - /** - * generate index array names (might be used for variable names) - */ - generateNames4RandomIndexPatterns(info->indexRandomPatterns); - - /** - * generate variable names - */ - //generate names for the independent variables - for (size_t j = 0; j < _independentSize; j++) { - Node& op = *info->independent[j]; - if (op.getName() == nullptr) { - op.setName(_nameGen->generateIndependent(op, getVariableID(op))); - } - } - - // generate names for the dependent variables (must be after naming independents) - for (size_t i = 0; i < dependent.size(); i++) { - Node* node = dependent[i].getOperationNode(); - if (node != nullptr && node->getOperationType() != CGOpCode::LoopEnd && node->getName() == nullptr) { - if (node->getOperationType() == CGOpCode::LoopIndexedDep) { - size_t pos = node->getInfo()[0]; - const IndexPattern* ip = info->loopDependentIndexPatterns[pos]; - node->setName(_nameGen->generateIndexedDependent(*node, getVariableID(*node), *ip)); - - } else { - node->setName(_nameGen->generateDependent(i)); - } - } - } - - /** - * function variable declaration - */ - const std::vector& indArg = _nameGen->getIndependent(); - const std::vector& depArg = _nameGen->getDependent(); - const std::vector& tmpArg = _nameGen->getTemporary(); - CPPADCG_ASSERT_KNOWN(indArg.size() > 0 && depArg.size() > 0, - "There must be at least one dependent and one independent argument"); - CPPADCG_ASSERT_KNOWN(tmpArg.size() == 3, - "There must be three temporary variables"); - - auxArrayName_ = tmpArg[1].name + "p"; - - /** - * Determine the dependent variables that result from the same operations - */ - // dependent variables indexes that are copies of other dependent variables - std::set dependentDuplicates; - - for (size_t i = 0; i < dependent.size(); i++) { - Node* node = dependent[i].getOperationNode(); - if (node != nullptr) { - CGOpCode type = node->getOperationType(); - if (type != CGOpCode::Inv && type != CGOpCode::LoopEnd) { - size_t varID = getVariableID(*node); - if (varID > 0) { - std::map::const_iterator it2 = _dependentIDs.find(varID); - if (it2 == _dependentIDs.end()) { - _dependentIDs[getVariableID(*node)] = i; - } else { - // there can be several dependent variables with the same ID - dependentDuplicates.insert(i); - } - } - } - } - } - - // the names of local functions - std::vector mathMLFiles; - if (multiFile) { - mathMLFiles.reserve(variableOrder.size() / _maxAssignmentsPerFile); - } - - /** - * non-constant variables - */ - if (variableOrder.size() > 0) { - // generate names for temporary variables - for (Node* node : variableOrder) { - CGOpCode op = node->getOperationType(); - if (!isDependent(*node) && op != CGOpCode::IndexDeclaration) { - // variable names for temporaries must always be created since they might have been used before with a different name/id - if (requiresVariableName(*node) && op != CGOpCode::ArrayCreation && op != CGOpCode::SparseArrayCreation) { - node->setName(_nameGen->generateTemporary(*node, getVariableID(*node))); - } else if (op == CGOpCode::ArrayCreation) { - node->setName(_nameGen->generateTemporaryArray(*node, getVariableID(*node))); - } else if (op == CGOpCode::SparseArrayCreation) { - node->setName(_nameGen->generateTemporarySparseArray(*node, getVariableID(*node))); - } - } - } - - /** - * Source code generation magic! - */ - if (info->zeroDependents) { - // zero initial values - const std::vector& depArg = _nameGen->getDependent(); - for (size_t i = 0; i < depArg.size(); i++) { - _code << _startEq; - const FuncArgument& a = depArg[i]; - if (a.array) { - _code << a.name; - } else { - _code << "" << _nameGen->generateDependent(i) << ""; - } - _code << _assignStr; - printParameter(Base(0.0)); - _code << _endEq << _endline; - } - } - - size_t assignCount = 0; - for (Node* it : variableOrder) { - // check if a new function should start - if (assignCount >= _maxAssignmentsPerFile && multiFile && _currentLoops.empty()) { - assignCount = 0; - saveLocalFunction(mathMLFiles, mathMLFiles.empty() && info->zeroDependents); - } - - Node& node = *it; - - // a dependent variable assigned by a loop does require any source code (its done inside the loop) - if (node.getOperationType() == CGOpCode::DependentRefRhs) { - continue; // nothing to do (this operation is right hand side only) - } else if (node.getOperationType() == CGOpCode::TmpDcl) { // temporary variable declaration does not need any source code here - continue; // nothing to do (bogus operation) - } - - assignCount += printAssignment(node); - } - - if (mathMLFiles.size() > 0 && assignCount > 0) { - assignCount = 0; - saveLocalFunction(mathMLFiles, false); - } - } - - if (!mathMLFiles.empty()) { - /** - * Create the master html file which inputs the other files - */ - CPPADCG_ASSERT_KNOWN(tmpArg[0].array, - "The temporary variables must be saved in an array in order to generate multiple functions"); - printAlgorithmFileStart(_code); - for (size_t i = 0; i < mathMLFiles.size(); i++) { - _code << "part " << (i + 1) << "
" << _endline; - } - printAlgorithmFileEnd(_code); - } - - // dependent duplicates - if (dependentDuplicates.size() > 0) { - _code << "" << _endline; - - for (size_t index : dependentDuplicates) { - const CG& dep = dependent[index]; - std::string varName = _nameGen->generateDependent(index); - Node* depNode = dep.getOperationNode(); - const std::string& origVarName = *depNode->getName(); - - _code << _startEq - << "" << varName << "" - << _assignStr - << "" << origVarName << ""; - printAssignmentEnd(); - } - } - - // constant dependent variables - bool commentWritten = false; - for (size_t i = 0; i < dependent.size(); i++) { - if (dependent[i].isParameter()) { - if (!_ignoreZeroDepAssign || !dependent[i].isIdenticalZero()) { - if (!commentWritten) { - _code << "" << _endline; - commentWritten = true; - } - - std::string depId = "d" + std::to_string(i); - if(_saveVariableRelations) { - depConstIds_.push_back(depId); - } - - std::string varName = _nameGen->generateDependent(i); - _code << _startEq - << "" << varName << "" << _assignStr; // id='" << createID(??) - printParameter(dependent[i].getValue()); - printAssignmentEnd(); - } - } else if (dependent[i].getOperationNode()->getOperationType() == CGOpCode::Inv) { - if (!commentWritten) { - _code << "" << _endline; - commentWritten = true; - } - - std::string varName = _nameGen->generateDependent(i); - const std::string& indepName = *dependent[i].getOperationNode()->getName(); - std::string depId = createID(dependent[i].getOperationNode()); - if(_saveVariableRelations) { - depIsIndepIds_.push_back(depId); - } - _code << _startEq - << "" << varName << "" - << _assignStr - << "" << indepName << ""; - printAssignmentEnd(*dependent[i].getOperationNode()); - } - } - - /** - * encapsulate the code in a function - */ - if (mathMLFiles.empty()) { - // a single source file - printAlgorithmFileStart(_ss); - _ss << _code.str(); - printAlgorithmFileEnd(_ss); - - out << _ss.str(); - - if (_sources != nullptr) { - (*_sources)[_filename + ".html"] = _ss.str(); - } - } else { - // there are multiple source files (this last one is the master) - (*_sources)[_filename + ".html"] = _code.str(); - } - - } - - inline size_t getVariableID(const Node& node) const { - return _info->varId[node]; - } - - inline virtual void printAlgorithmFileStart(std::ostream& out) { - out << "" << _endline << - "" << _endline << - "" << _endline << - "" << _endline << - "" << _filename << "" << _endline; - - if (!_headExtra.empty()) { - out << _headExtra << _endline; - } - - if (!_style.empty()) { - out << "" << _endline; - } - - if(_saveVariableRelations) { - CPPADCG_ASSERT_UNKNOWN(_info->variableDependencies.size() == _info->variableOrder.size()); - - out << "" << _endline; - } - - if (!_javascript.empty()) { - out << "" << _endline; - } - - out << "" << _endline << - "" << _endline << - "" << _endline << - "" << _endline << - "
" << _endline; - } - - inline virtual void printAlgorithmFileEnd(std::ostream& out) { - - if(_saveVariableRelations) { - out << "" << _endline; - } - - out << "
" << _endline << - "" << _endline << - ""; - } - - inline unsigned printAssignment(Node& node) { - return printAssignment(node, node); - } - - inline unsigned printAssignment(Node& nodeName, - const Arg& nodeRhs) { - if (nodeRhs.getOperation() != nullptr) { - return printAssignment(nodeName, *nodeRhs.getOperation()); - } else { - printAssignmentStart(nodeName); - printParameter(*nodeRhs.getParameter()); - printAssignmentEnd(nodeName); - return 1; - } - } - - inline unsigned printAssignment(Node& nodeName, - Node& nodeRhs) { - bool createsVar = directlyAssignsVariable(nodeRhs); // do we need to do the assignment here? - if (!createsVar) { - printAssignmentStart(nodeName); - } - unsigned lines = printExpressionNoVarCheck(nodeRhs); - if (!createsVar) { - printAssignmentEnd(nodeRhs); - } - - if (nodeRhs.getOperationType() == CGOpCode::ArrayElement) { - Node* array = nodeRhs.getArguments()[0].getOperation(); - size_t arrayId = getVariableID(*array); - size_t pos = nodeRhs.getInfo()[0]; - if (array->getOperationType() == CGOpCode::ArrayCreation) - _tmpArrayValues[arrayId - 1 + pos] = nullptr; // this could probably be removed! - else - _tmpSparseArrayValues[arrayId - 1 + pos] = nullptr; // this could probably be removed! - } - - return lines; - } - - inline virtual void printAssignmentStart(Node& op) { - printAssignmentStart(op, createVariableName(op), isDependent(op)); - } - - inline virtual void printAssignmentStart(Node& node, const std::string& varName, bool isDep) { - if (!isDep) { - _temporary[getVariableID(node)] = &node; - } - - _code << _startEq; - _code << "" << varName << ""; - - CGOpCode op = node.getOperationType(); - if (op == CGOpCode::DependentMultiAssign || (op == CGOpCode::LoopIndexedDep && node.getInfo()[1] == 1)) { - _code << _assignAddStr; // += - } else { - _code << _assignStr; // = - } - } - - inline virtual void printAssignmentEnd() { - _code << _endEq << _endline; - } - - inline virtual void printAssignmentEnd(Node& op) { - printAssignmentEnd(); - } - - virtual void saveLocalFunction(std::vector& localFuncNames, - bool zeroDependentArray) { - _ss << _filename << "__part_" << (localFuncNames.size() + 1); - std::string funcName = _ss.str(); - _ss.str(""); - - // loop indexes - _nameGen->prepareCustomFunctionVariables(_ss); - _ss << _code.str(); - _nameGen->finalizeCustomFunctionVariables(_ss); - - (*_sources)[funcName + ".html"] = _ss.str(); - localFuncNames.push_back(funcName); - - _code.str(""); - _ss.str(""); - } - - virtual bool createsNewVariable(const Node& var, - size_t totalUseCount) const override { - CGOpCode op = var.getOperationType(); - if (totalUseCount > 1) { - return op != CGOpCode::ArrayElement && op != CGOpCode::Index && op != CGOpCode::IndexDeclaration && op != CGOpCode::Tmp; - } else { - return ( op == CGOpCode::ArrayCreation || - op == CGOpCode::SparseArrayCreation || - op == CGOpCode::AtomicForward || - op == CGOpCode::AtomicReverse || - op == CGOpCode::ComLt || - op == CGOpCode::ComLe || - op == CGOpCode::ComEq || - op == CGOpCode::ComGe || - op == CGOpCode::ComGt || - op == CGOpCode::ComNe || - op == CGOpCode::LoopIndexedDep || - op == CGOpCode::LoopIndexedTmp || - op == CGOpCode::IndexAssign || - op == CGOpCode::Assign) && - op != CGOpCode::CondResult; - } - } - - virtual bool requiresVariableName(const Node& var) const { - CGOpCode op = var.getOperationType(); - return (_info->totalUseCount.get(var) > 1 && - op != CGOpCode::AtomicForward && - op != CGOpCode::AtomicReverse && - op != CGOpCode::LoopStart && - op != CGOpCode::LoopEnd && - op != CGOpCode::Index && - op != CGOpCode::IndexAssign && - op != CGOpCode::StartIf && - op != CGOpCode::ElseIf && - op != CGOpCode::Else && - op != CGOpCode::EndIf && - op != CGOpCode::CondResult && - op != CGOpCode::LoopIndexedTmp && - op != CGOpCode::Tmp); - } - - /** - * Whether or not this operation assign its expression to a variable by - * itself. - * - * @param var the operation node - * @return - */ - virtual bool directlyAssignsVariable(const Node& var) const { - CGOpCode op = var.getOperationType(); - return isCondAssign(op) || - op == CGOpCode::ArrayCreation || - op == CGOpCode::SparseArrayCreation || - op == CGOpCode::AtomicForward || - op == CGOpCode::AtomicReverse || - op == CGOpCode::DependentMultiAssign || - op == CGOpCode::LoopStart || - op == CGOpCode::LoopEnd || - op == CGOpCode::IndexAssign || - op == CGOpCode::StartIf || - op == CGOpCode::ElseIf || - op == CGOpCode::Else || - op == CGOpCode::EndIf || - op == CGOpCode::CondResult || - op == CGOpCode::IndexDeclaration; - } - - virtual bool requiresVariableArgument(enum CGOpCode op, size_t argIndex) const override { - return op == CGOpCode::CondResult; - } - - inline const std::string& createVariableName(Node& var) { - CGOpCode op = var.getOperationType(); - CPPADCG_ASSERT_UNKNOWN(getVariableID(var) > 0); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::AtomicForward); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::AtomicReverse); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::LoopStart); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::LoopEnd); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::Index); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::IndexAssign); - CPPADCG_ASSERT_UNKNOWN(op != CGOpCode::IndexDeclaration); - - if (var.getName() == nullptr) { - if (op == CGOpCode::ArrayCreation) { - var.setName(_nameGen->generateTemporaryArray(var, getVariableID(var))); - - } else if (op == CGOpCode::SparseArrayCreation) { - var.setName(_nameGen->generateTemporarySparseArray(var, getVariableID(var))); - - } else if (op == CGOpCode::LoopIndexedDep) { - size_t pos = var.getInfo()[0]; - const IndexPattern* ip = _info->loopDependentIndexPatterns[pos]; - var.setName(_nameGen->generateIndexedDependent(var, getVariableID(var), *ip)); - - } else if (op == CGOpCode::LoopIndexedIndep) { - size_t pos = var.getInfo()[1]; - const IndexPattern* ip = _info->loopIndependentIndexPatterns[pos]; - var.setName(_nameGen->generateIndexedIndependent(var, getVariableID(var), *ip)); - - } else if (getVariableID(var) <= _independentSize) { - // independent variable - var.setName(_nameGen->generateIndependent(var, getVariableID(var))); - - } else if (getVariableID(var) < _minTemporaryVarID) { - // dependent variable - std::map::const_iterator it = _dependentIDs.find(getVariableID(var)); - CPPADCG_ASSERT_UNKNOWN(it != _dependentIDs.end()); - - size_t index = it->second; - var.setName(_nameGen->generateDependent(index)); - - } else if (op == CGOpCode::LoopIndexedTmp || op == CGOpCode::Tmp) { - CPPADCG_ASSERT_KNOWN(var.getArguments().size() >= 1, "Invalid number of arguments for loop indexed temporary operation"); - Node* tmpVar = var.getArguments()[0].getOperation(); - CPPADCG_ASSERT_KNOWN(tmpVar != nullptr && tmpVar->getOperationType() == CGOpCode::TmpDcl, "Invalid arguments for loop indexed temporary operation"); - return createVariableName(*tmpVar); - - } else { - // temporary variable - var.setName(_nameGen->generateTemporary(var, getVariableID(var))); - } - } - - - return *var.getName(); - } - - inline std::string createID(const Node* var) { - return createID(*var); - } - - virtual std::string createID(const Node& var) { - size_t id = getVariableID(var); - if (varIds_.size() <= id) { - varIds_.resize(id + 1 + varIds_.size() * 3 / 2, 0); - } - - int n = varIds_[id]; - varIds_[id]++; - - if (n == 0) - return "v" + std::to_string(id); - else - return "v" + std::to_string(id) + "_" + std::to_string(n); - } - - virtual void printIndependentVariableName(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 0, "Invalid number of arguments for independent variable"); - //size_t id = getVariableID(op); - _code << "" << _nameGen->generateIndependent(op, getVariableID(op)) << ""; - } - - virtual unsigned print(const Arg& arg) { - if (arg.getOperation() != nullptr) { - // expression - return printExpression(*arg.getOperation()); - } else { - // parameter - printParameter(*arg.getParameter()); - return 1; - } - } - - virtual unsigned printExpression(Node& node) { - if (getVariableID(node) > 0) { - const std::string& name = createVariableName(node); // use variable name - //size_t id = getVariableID(node); - - CGOpCode op = node.getOperationType(); - if (getVariableID(node) >= _minTemporaryVarID || op == CGOpCode::ArrayCreation || op == CGOpCode::SparseArrayCreation || op == CGOpCode::LoopIndexedDep || op == CGOpCode::LoopIndexedIndep) { - - _code << "" << name << ""; // TODO!!!!!!!!!!!!!!!!!!!!!!! - - } else if (getVariableID(node) <= _independentSize) { - // independent variable - _code << "" << name << ""; - - } else { - // dependent variable - _code << "" << name << ""; - - } - - return 1; - } else { - // print expression code - return printExpressionNoVarCheck(node); - } - } - - virtual unsigned printExpressionNoVarCheck(Node& node) { - CGOpCode op = node.getOperationType(); - switch (op) { - case CGOpCode::ArrayCreation: - printArrayCreationOp(node); - break; - case CGOpCode::SparseArrayCreation: - printSparseArrayCreationOp(node); - break; - case CGOpCode::ArrayElement: - printArrayElementOp(node); - break; - case CGOpCode::Assign: - return printAssignOp(node); - - case CGOpCode::Abs: - case CGOpCode::Acos: - case CGOpCode::Asin: - case CGOpCode::Atan: - case CGOpCode::Cosh: - case CGOpCode::Cos: - case CGOpCode::Exp: - case CGOpCode::Log: - case CGOpCode::Sign: - case CGOpCode::Sinh: - case CGOpCode::Sin: - case CGOpCode::Sqrt: - case CGOpCode::Tanh: - case CGOpCode::Tan: - printUnaryFunction(node); - break; - case CGOpCode::AtomicForward: // atomicFunction.forward(q, p, vx, vy, tx, ty) - printAtomicForwardOp(node); - break; - case CGOpCode::AtomicReverse: // atomicFunction.reverse(p, tx, ty, px, py) - printAtomicReverseOp(node); - break; - case CGOpCode::Add: - printOperationAdd(node); - break; - case CGOpCode::Alias: - return printOperationAlias(node); - - case CGOpCode::ComLt: - case CGOpCode::ComLe: - case CGOpCode::ComEq: - case CGOpCode::ComGe: - case CGOpCode::ComGt: - case CGOpCode::ComNe: - printConditionalAssignment(node); - break; - case CGOpCode::Div: - printOperationDiv(node); - break; - case CGOpCode::Inv: - printIndependentVariableName(node); - break; - case CGOpCode::Mul: - printOperationMul(node); - break; - case CGOpCode::Pow: - printPowFunction(node); - break; - case CGOpCode::Pri: - // do nothing - break; - case CGOpCode::Sub: - printOperationMinus(node); - break; - - case CGOpCode::UnMinus: - printOperationUnaryMinus(node); - break; - - case CGOpCode::DependentMultiAssign: - return printDependentMultiAssign(node); - - case CGOpCode::Index: - return 0; // nothing to do - case CGOpCode::IndexAssign: - printIndexAssign(node); - break; - case CGOpCode::IndexDeclaration: - return 0; // already done - - case CGOpCode::LoopStart: - printLoopStart(node); - break; - case CGOpCode::LoopIndexedIndep: - printLoopIndexedIndep(node); - break; - case CGOpCode::LoopIndexedDep: - printLoopIndexedDep(node); - break; - case CGOpCode::LoopIndexedTmp: - printLoopIndexedTmp(node); - break; - case CGOpCode::TmpDcl: - // nothing to do - return 0; - case CGOpCode::Tmp: - printTmpVar(node); - break; - case CGOpCode::LoopEnd: - printLoopEnd(node); - break; - case CGOpCode::IndexCondExpr: - printIndexCondExprOp(node); - break; - case CGOpCode::StartIf: - printStartIf(node); - break; - case CGOpCode::ElseIf: - printElseIf(node); - break; - case CGOpCode::Else: - printElse(node); - break; - case CGOpCode::EndIf: - printEndIf(node); - break; - case CGOpCode::CondResult: - printCondResult(node); - break; - case CGOpCode::UserCustom: - printUserCustom(node); - break; - default: - throw CGException("Unknown operation code '", op, "'."); - } - return 1; - } - - virtual unsigned printAssignOp(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 1, "Invalid number of arguments for assign operation"); - - return print(node.getArguments()[0]); - } - - virtual void printUnaryFunction(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 1, "Invalid number of arguments for unary function"); - - switch (op.getOperationType()) { - case CGOpCode::Abs: - _code << "abs"; - break; - case CGOpCode::Acos: - _code << "arccos"; - break; - case CGOpCode::Asin: - _code << "arcsin"; - break; - case CGOpCode::Atan: - _code << "arctan"; - break; - case CGOpCode::Cosh: - _code << "cosh"; - break; - case CGOpCode::Cos: - _code << "cos"; - break; - case CGOpCode::Exp: - _code << "exp"; ///////////////////////////////////////// consider using superscript - break; - case CGOpCode::Log: - _code << "ln"; - break; - case CGOpCode::Sinh: - _code << "sinh"; - break; - case CGOpCode::Sign: - _code << "sgn"; - break; - case CGOpCode::Sin: - _code << "sin"; - break; - case CGOpCode::Sqrt: - _code << ""; - print(op.getArguments()[0]); - _code << ""; - return; - case CGOpCode::Tanh: - _code << "tanh"; - break; - case CGOpCode::Tan: - _code << "tan"; - break; - default: - throw CGException("Unknown function name for operation code '", op.getOperationType(), "'."); - } - - _code << "" - ""; - print(op.getArguments()[0]); - _code << ""; - } - - virtual void printPowFunction(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for pow() function"); - - auto encloseInParentheses = [this](const Node* node) { - while (node != nullptr) { - if (getVariableID(*node) != 0) - return false; - if (node->getOperationType() == CGOpCode::Alias) - node = node->getArguments()[0].getOperation(); - else - break; - } - return node != nullptr && - getVariableID(*node) == 0 && - !isFunction(node->getOperationType()); - }; - - - bool encloseBase = _powBaseEnclose || encloseInParentheses(op.getArguments()[0].getOperation()); - bool encloseExpo = encloseInParentheses(op.getArguments()[1].getOperation()); - - _code << ""; - if (encloseBase) - _code << ""; - _code << ""; - print(op.getArguments()[0]); - _code << ""; - if (encloseBase) - _code << ""; - if (encloseExpo) - _code << ""; - _code << ""; - print(op.getArguments()[1]); - _code << ""; - if (encloseExpo) - _code << ""; - _code << ""; - } - - virtual unsigned printOperationAlias(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 1, "Invalid number of arguments for alias"); - return print(op.getArguments()[0]); - } - - virtual void printOperationAdd(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for addition"); - - const Arg& left = op.getArguments()[0]; - const Arg& right = op.getArguments()[1]; - - if(right.getParameter() == nullptr || (*right.getParameter() >= 0)) { - print(left); - _code << "+"; - print(right); - } else { - // right has a negative parameter so we would get v0 + -v1 - print(left); - _code << "-"; - printParameter(-*right.getParameter()); // make it positive - } - } - - virtual void printOperationMinus(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for subtraction"); - - const Arg& left = op.getArguments()[0]; - const Arg& right = op.getArguments()[1]; - - // whether or not to flip + to - and change sign - if(right.getParameter() == nullptr || (*right.getParameter() >= 0)) { - bool encloseRight = encloseInParenthesesMul(right); - - print(left); - _code << "-"; - if (encloseRight) { - _code << ""; - } - print(right); - if (encloseRight) { - _code << ""; - } - } else { - // right has a negative parameter so we would get v0 - -v1 - print(left); - _code << "+"; - printParameter(-*right.getParameter()); // make it positive - } - } - - virtual void printOperationDiv(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for division"); - - const Arg& left = op.getArguments()[0]; - const Arg& right = op.getArguments()[1]; - - _code << ""; - _code << ""; - print(left); - _code << ""; - _code << ""; - print(right); - _code << ""; - _code << ""; - } - - inline bool encloseInParenthesesMul(const Arg& arg) const { - if (arg.getParameter() != nullptr) { - return ((*arg.getParameter()) < 0); - } else { - return encloseInParenthesesMul(arg.getOperation()); - } - } - - inline bool encloseInParenthesesMul(const Node* node) const { - while (node != nullptr) { - if (getVariableID(*node) != 0) { - return false; - } else if (node->getOperationType() == CGOpCode::Alias) { - node = node->getArguments()[0].getOperation(); - } else { - break; - } - } - return node != nullptr && - getVariableID(*node) == 0 && - node->getOperationType() != CGOpCode::Div && - node->getOperationType() != CGOpCode::Mul && - !isFunction(node->getOperationType()); - } - - virtual void printOperationMul(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for multiplication"); - - const Arg& left = op.getArguments()[0]; - const Arg& right = op.getArguments()[1]; - - bool encloseLeft = encloseInParenthesesMul(left); - bool encloseRight = encloseInParenthesesMul(right); - - auto isNumber = [this](const Node* node, int pos) -> bool { - while (node != nullptr) { - if(getVariableID(*node) != 0) { - return false; - } - CGOpCode op = node->getOperationType(); - if (op == CGOpCode::Alias) { - node = node->getArguments()[0].getOperation(); - continue; - } else if (op == CGOpCode::Mul) { - node = node->getArguments()[pos].getOperation(); - } else if (pos == 0 && op == CGOpCode::Pow) { - node = node->getArguments()[0].getOperation(); - } else { - return false; - } - } - return true; // a constant number - }; - - if (encloseLeft) { - _code << ""; - } - print(left); - if (encloseLeft) { - _code << ""; - } - - if (isNumber(left.getOperation(), 1) && isNumber(right.getOperation(), 0)) - _code << _multValOpStr; // numbers too close together are difficult to distinguish - else - _code << _multOpStr; // e.g. invisible times - - if (encloseRight) { - _code << ""; - } - print(right); - if (encloseRight) { - _code << ""; - } - } - - virtual void printOperationUnaryMinus(Node& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 1, "Invalid number of arguments for unary minus"); - - const Arg& arg = op.getArguments()[0]; - - bool enclose = encloseInParenthesesMul(arg); - - _code << "-"; - if (enclose) { - _code << ""; - } - print(arg); - if (enclose) { - _code << ""; - } - } - - virtual void printConditionalAssignment(Node& node) { - CPPADCG_ASSERT_UNKNOWN(getVariableID(node) > 0); - - const std::vector& args = node.getArguments(); - const Arg &left = args[0]; - const Arg &right = args[1]; - const Arg &trueCase = args[2]; - const Arg &falseCase = args[3]; - - bool isDep = isDependent(node); - const std::string& varName = createVariableName(node); - - if ((trueCase.getParameter() != nullptr && falseCase.getParameter() != nullptr && *trueCase.getParameter() == *falseCase.getParameter()) || - (trueCase.getOperation() != nullptr && falseCase.getOperation() != nullptr && trueCase.getOperation() == falseCase.getOperation())) { - // true and false cases are the same - printAssignmentStart(node, varName, isDep); - print(trueCase); - printAssignmentEnd(node); - } else { - - _code << _ifStart << _startEq << "if" - ""; - print(left); - _code << ""; - getComparison(_code, node.getOperationType()); - _code << ""; - print(right); - _code << "" << _endEq << _endline - << _condBodyStart << _endline; - - //checkEquationEnvStart(); // no need - printAssignmentStart(node, varName, isDep); - print(trueCase); - printAssignmentEnd(node); - _code << _condBodyEnd << _endline << _ifEnd << _endline; - - // else - _code << _elseStart << _startEq << "else" << _endEq << _endline - << _condBodyStart << _endline; - //checkEquationEnvStart(); // no need - printAssignmentStart(node, varName, isDep); - print(falseCase); - printAssignmentEnd(node); - _code << _condBodyEnd << _endline << _elseEnd << _endline; // end if - } - } - - inline bool isSameArgument(const Arg& newArg, - const Arg* oldArg) { - if (oldArg != nullptr) { - if (oldArg->getParameter() != nullptr) { - if (newArg.getParameter() != nullptr) { - return (*newArg.getParameter() == *oldArg->getParameter()); - } - } else { - return (newArg.getOperation() == oldArg->getOperation()); - } - } - return false; - } - - virtual void printArrayCreationOp(Node& op); - - virtual void printSparseArrayCreationOp(Node& op); - - inline void printArrayStructInit(const std::string& dataArrayName, - size_t pos, - const std::vector& arrays, - size_t k); - - inline void printArrayStructInit(const std::string& dataArrayName, - Node& array); - - inline void markArrayChanged(Node& ty); - - inline size_t printArrayCreationUsingLoop(size_t startPos, - Node& array, - size_t startj, - std::vector& tmpArrayValues); - - inline std::string getTempArrayName(const Node& op); - - virtual void printArrayElementOp(Node& op); - - virtual void printAtomicForwardOp(Node& atomicFor) { - CPPADCG_ASSERT_KNOWN(atomicFor.getInfo().size() == 3, "Invalid number of information elements for atomic forward operation"); - int q = atomicFor.getInfo()[1]; - int p = atomicFor.getInfo()[2]; - size_t p1 = p + 1; - const std::vector& opArgs = atomicFor.getArguments(); - CPPADCG_ASSERT_KNOWN(opArgs.size() == p1 * 2, "Invalid number of arguments for atomic forward operation"); - - size_t id = atomicFor.getInfo()[0]; - std::vector tx(p1), ty(p1); - for (size_t k = 0; k < p1; k++) { - tx[k] = opArgs[0 * p1 + k].getOperation(); - ty[k] = opArgs[1 * p1 + k].getOperation(); - } - - CPPADCG_ASSERT_KNOWN(tx[0]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - CPPADCG_ASSERT_KNOWN(p == 0 || tx[1]->getOperationType() == CGOpCode::SparseArrayCreation, "Invalid array type"); - CPPADCG_ASSERT_KNOWN(ty[p]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - - // tx - for (size_t k = 0; k < p1; k++) { - printArrayStructInit(_ATOMIC_TX, k, tx, k); - } - // ty - printArrayStructInit(_ATOMIC_TY, *ty[p]); - _ss.str(""); - - _code << _startEq - << _info->atomicFunctionId2Name.at(id) << ".forward" - "" - "" << q << "" - "" << p << "" - "" << _ATOMIC_TX << "" - "&" << _ATOMIC_TY << "" - "" - << _endEq << _endline; - - /** - * the values of ty are now changed - */ - markArrayChanged(*ty[p]); - } - - virtual void printAtomicReverseOp(Node& atomicRev) { - CPPADCG_ASSERT_KNOWN(atomicRev.getInfo().size() == 2, "Invalid number of information elements for atomic reverse operation"); - int p = atomicRev.getInfo()[1]; - size_t p1 = p + 1; - const std::vector& opArgs = atomicRev.getArguments(); - CPPADCG_ASSERT_KNOWN(opArgs.size() == p1 * 4, "Invalid number of arguments for atomic reverse operation"); - - size_t id = atomicRev.getInfo()[0]; - std::vector tx(p1), px(p1), py(p1); - for (size_t k = 0; k < p1; k++) { - tx[k] = opArgs[0 * p1 + k].getOperation(); - px[k] = opArgs[2 * p1 + k].getOperation(); - py[k] = opArgs[3 * p1 + k].getOperation(); - } - - CPPADCG_ASSERT_KNOWN(tx[0]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - CPPADCG_ASSERT_KNOWN(p == 0 || tx[1]->getOperationType() == CGOpCode::SparseArrayCreation, "Invalid array type"); - - CPPADCG_ASSERT_KNOWN(px[0]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - - CPPADCG_ASSERT_KNOWN(py[0]->getOperationType() == CGOpCode::SparseArrayCreation, "Invalid array type"); - CPPADCG_ASSERT_KNOWN(p == 0 || py[1]->getOperationType() == CGOpCode::ArrayCreation, "Invalid array type"); - - // tx - for (size_t k = 0; k < p1; k++) { - printArrayStructInit(_ATOMIC_TX, k, tx, k); - } - // py - for (size_t k = 0; k < p1; k++) { - printArrayStructInit(_ATOMIC_PY, k, py, k); - } - // px - printArrayStructInit(_ATOMIC_PX, *px[0]); - _ss.str(""); - - _code << _startEq - << _info->atomicFunctionId2Name.at(id) << ".reverse" - "" - "" << p << "" - "" << _ATOMIC_TX << "" - "&" << _ATOMIC_PX << "" - "" << _ATOMIC_PY << "" - "" - << _endEq << _endline; - - /** - * the values of px are now changed - */ - markArrayChanged(*px[0]); - } - - virtual unsigned printDependentMultiAssign(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::DependentMultiAssign, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() > 0, "Invalid number of arguments"); - - const std::vector& args = node.getArguments(); - for (size_t a = 0; a < args.size(); a++) { - bool useArg = false; - const Arg& arg = args[a]; - if (arg.getParameter() != nullptr) { - useArg = true; - } else { - CGOpCode op = arg.getOperation()->getOperationType(); - useArg = op != CGOpCode::DependentRefRhs && op != CGOpCode::LoopEnd && op != CGOpCode::EndIf; - } - - if (useArg) { - printAssignment(node, arg); // ignore other arguments! - return 1; - } - } - return 0; - } - - virtual void printLoopStart(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopStart, "Invalid node type"); - - LoopStartOperationNode& lnode = static_cast&> (node); - _currentLoops.push_back(&lnode); - - const std::string& jj = *lnode.getIndex().getName(); - std::string lastIt; - if (lnode.getIterationCountNode() != nullptr) { - lastIt = *lnode.getIterationCountNode()->getIndex().getName() + " - 1"; - } else { - lastIt = "" + std::to_string(lnode.getIterationCount() - 1) + ""; - } - - _code << _forStart << _startEq << "for" - "" - << jj << "" - "" - "0" << lastIt << - "" - "" << _endEq << _endline - << _forBodyStart; - _indentationLevel++; - } - - virtual void printLoopEnd(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopEnd, "Invalid node type"); - - _indentationLevel--; - - _code << _forBodyEnd << _forEnd << _endline; - - _currentLoops.pop_back(); - } - - virtual void printLoopIndexedDep(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 1, "Invalid number of arguments for loop indexed dependent operation"); - - // LoopIndexedDep - print(node.getArguments()[0]); - } - - virtual void printLoopIndexedIndep(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopIndexedIndep, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getInfo().size() == 1, "Invalid number of information elements for loop indexed independent operation"); - - // CGLoopIndexedIndepOp - size_t pos = node.getInfo()[1]; - const IndexPattern* ip = _info->loopIndependentIndexPatterns[pos]; - _code << _nameGen->generateIndexedIndependent(node, getVariableID(node), *ip); - } - - virtual void printLoopIndexedTmp(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::LoopIndexedTmp, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 2, "Invalid number of arguments for loop indexed temporary operation"); - Node* tmpVar = node.getArguments()[0].getOperation(); - CPPADCG_ASSERT_KNOWN(tmpVar != nullptr && tmpVar->getOperationType() == CGOpCode::TmpDcl, "Invalid arguments for loop indexed temporary operation"); - - print(node.getArguments()[1]); - } - - virtual void printTmpVar(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::Tmp, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() > 0, "Invalid number of arguments for temporary variable usage operation"); - Node* tmpVar = node.getArguments()[0].getOperation(); - CPPADCG_ASSERT_KNOWN(tmpVar != nullptr && tmpVar->getOperationType() == CGOpCode::TmpDcl, "Invalid arguments for loop indexed temporary operation"); - - _code << "" << *tmpVar->getName() << ""; - } - - virtual void printIndexAssign(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::IndexAssign, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() > 0, "Invalid number of arguments for an index assignment operation"); - - IndexAssignOperationNode& inode = static_cast&> (node); - - const IndexPattern& ip = inode.getIndexPattern(); - _code << _startEq - << (*inode.getIndex().getName()) - << _assignStr; - indexPattern2String(_code, ip, inode.getIndexPatternIndexes()); - _code << _endEq << _endline; - } - - virtual void printIndexCondExprOp(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::IndexCondExpr, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 1, "Invalid number of arguments for an index condition expression operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an index condition expression operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation()->getOperationType() == CGOpCode::Index, "Invalid argument for an index condition expression operation"); - - const std::vector& info = node.getInfo(); - - IndexOperationNode& iterationIndexOp = static_cast&> (*node.getArguments()[0].getOperation()); - const std::string& index = *iterationIndexOp.getIndex().getName(); - - printIndexCondExpr(_code, info, index); - } - - virtual void printStartIf(Node& node) { - /** - * the first argument is the condition, following arguments are - * just extra dependencies that must be defined outside the if - */ - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::StartIf, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 1, "Invalid number of arguments for an 'if start' operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an 'if start' operation"); - - _code << _ifStart << _startEq << "if" - ""; - printIndexCondExprOp(*node.getArguments()[0].getOperation()); - _code << "" << _endEq << _endline - << _condBodyStart << _endline; - - _indentationLevel++; - } - - virtual void printElseIf(Node& node) { - /** - * the first argument is the condition, the second argument is the - * if start node, the following arguments are assignments in the - * previous if branch - */ - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::ElseIf, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 2, "Invalid number of arguments for an 'else if' operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an 'else if' operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[1].getOperation() != nullptr, "Invalid argument for an 'else if' operation"); - - _indentationLevel--; - - // close previous environment - _code << _condBodyEnd << _endline; - CGOpCode nType = node.getArguments()[0].getOperation()->getOperationType(); - if (nType == CGOpCode::StartIf) { - _code << _ifEnd << _endline; - } else if (nType == CGOpCode::ElseIf) { - _code << _elseIfEnd << _endline; - } - - // start new else if - _code << _elseIfStart << _startEq << "else if" - ""; - printIndexCondExprOp(*node.getArguments()[1].getOperation()); - _code << "" << _endEq << _endline - << _condBodyStart << _endline; - - _indentationLevel++; - } - - virtual void printElse(Node& node) { - /** - * the first argument is the if start node, the following arguments - * are assignments in the previous if branch - */ - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::Else, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() >= 1, "Invalid number of arguments for an 'else' operation"); - - _indentationLevel--; - - // close previous environment - _code << _condBodyEnd << _endline; - CGOpCode nType = node.getArguments()[0].getOperation()->getOperationType(); - if (nType == CGOpCode::StartIf) { - _code << _ifEnd << _endline; - } else if (nType == CGOpCode::ElseIf) { - _code << _elseIfEnd << _endline; - } - - // start else - _code << _elseStart << _startEq << "else" << _endEq << _endline - << _condBodyStart << _endline; - _code << _elseStart; - - _indentationLevel++; - } - - virtual void printEndIf(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::EndIf, "Invalid node type for an 'end if' operation"); - - _indentationLevel--; - - // close previous environment - _code << _condBodyEnd << _endline; - CGOpCode nType = node.getArguments()[0].getOperation()->getOperationType(); - if (nType == CGOpCode::StartIf) { - _code << _ifEnd << _endline; - } else if (nType == CGOpCode::ElseIf) { - _code << _elseIfEnd << _endline; - } else { - assert(nType == CGOpCode::Else); - _code << _elseEnd << _endline; - } - } - - virtual void printCondResult(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::CondResult, "Invalid node type"); - CPPADCG_ASSERT_KNOWN(node.getArguments().size() == 2, "Invalid number of arguments for an assignment inside an if/else operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[0].getOperation() != nullptr, "Invalid argument for an an assignment inside an if/else operation"); - CPPADCG_ASSERT_KNOWN(node.getArguments()[1].getOperation() != nullptr, "Invalid argument for an an assignment inside an if/else operation"); - - // just follow the argument - Node& nodeArg = *node.getArguments()[1].getOperation(); - printAssignment(nodeArg); - } - - virtual void printUserCustom(Node& node) { - CPPADCG_ASSERT_KNOWN(node.getOperationType() == CGOpCode::UserCustom, "Invalid node type"); - - throw CGException("Unable to generate MathML for user custom operation nodes."); - } - - inline bool isDependent(const Node& arg) const { - if (arg.getOperationType() == CGOpCode::LoopIndexedDep) { - return true; - } - size_t id = getVariableID(arg); - return id > _independentSize && id < _minTemporaryVarID; - } - - virtual void printParameter(const Base& value) { - // make sure all digits of floating point values are printed - std::ostringstream os; - os << std::setprecision(_parameterPrecision) << value; - - std::string number = os.str(); - size_t pos = number.find('e'); - if (pos != std::string::npos) { - _code << "" << number.substr(0, pos) << "×"; - _code << "10"; - pos++; - if (number[pos] == '-') { - _code << "-"; - pos++; - } else if (number[pos] == '+') { - pos++; - } - while (pos < number.size() - 1 && number[pos] == '0') - pos++; // remove zeros - - _code << number.substr(pos) << ""; - - } else { - _code << "" << number << ""; - } - - - } - - virtual void getComparison(std::ostream& os, enum CGOpCode op) const { - switch (op) { - case CGOpCode::ComLt: - os << "<"; - return; - - case CGOpCode::ComLe: - os << "≤"; - return; - - case CGOpCode::ComEq: - os << "=="; - return; - - case CGOpCode::ComGe: - os << "≥"; - return; - - case CGOpCode::ComGt: - os << ">"; - return; - - case CGOpCode::ComNe: - os << "≠"; - return; - - default: - CPPAD_ASSERT_UNKNOWN(0); - } - throw CGException("Invalid comparison operator code"); // should never get here - } - - static bool isFunction(enum CGOpCode op) { - return isUnaryFunction(op) || op == CGOpCode::Pow; - } - - static bool isUnaryFunction(enum CGOpCode op) { - switch (op) { - case CGOpCode::Abs: - case CGOpCode::Acos: - case CGOpCode::Asin: - case CGOpCode::Atan: - case CGOpCode::Cosh: - case CGOpCode::Cos: - case CGOpCode::Exp: - case CGOpCode::Log: - case CGOpCode::Sign: - case CGOpCode::Sinh: - case CGOpCode::Sin: - case CGOpCode::Sqrt: - case CGOpCode::Tanh: - case CGOpCode::Tan: - return true; - default: - return false; - } - } - - static bool isCondAssign(enum CGOpCode op) { - switch (op) { - case CGOpCode::ComLt: - case CGOpCode::ComLe: - case CGOpCode::ComEq: - case CGOpCode::ComGe: - case CGOpCode::ComGt: - case CGOpCode::ComNe: - return true; - default: - return false; - } - } -}; - -template -const std::string LanguageMathML::_C_STATIC_INDEX_ARRAY = "index"; - -template -const std::string LanguageMathML::_C_SPARSE_INDEX_ARRAY = "idx"; - -template -const std::string LanguageMathML::_ATOMIC_TX = "atx"; - -template -const std::string LanguageMathML::_ATOMIC_TY = "aty"; - -template -const std::string LanguageMathML::_ATOMIC_PX = "apx"; - -template -const std::string LanguageMathML::_ATOMIC_PY = "apy"; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/mathml/language_mathml_arrays.hpp b/ct_core/include/ct/external/cppad/cg/lang/mathml/language_mathml_arrays.hpp deleted file mode 100644 index 250a14308..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/mathml/language_mathml_arrays.hpp +++ /dev/null @@ -1,376 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_MATHML_ARRAYS_INCLUDED -#define CPPAD_CG_LANGUAGE_MATHML_ARRAYS_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2015 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -void LanguageMathML::printArrayCreationOp(OperationNode& array) { - CPPADCG_ASSERT_KNOWN(array.getArguments().size() > 0, "Invalid number of arguments for array creation operation"); - const size_t id = getVariableID(array); - const std::vector >& args = array.getArguments(); - const size_t argSize = args.size(); - - size_t startPos = id - 1; - - bool firstElement = true; - for (size_t i = 0; i < argSize; i++) { - bool newValue = !isSameArgument(args[i], _tmpArrayValues[startPos + i]); - - if (newValue) { - if (firstElement) { - _code << _startEq - << "" << auxArrayName_ << "" << _assignStr << _nameGen->generateTemporaryArray(array, getVariableID(array)) - << _endEq - << " " << _endline; - firstElement = false; - } - - // try to use a loop for element assignment - size_t newI = printArrayCreationUsingLoop(startPos, array, i, _tmpArrayValues); - - // print elements not assign in a loop - if (newI == i) { - // individual element assignment - _code << _startEq - << "" << auxArrayName_ << "" << i << "" << _assignStr; - print(args[i]); - _code << _endEq << _endline; - - _tmpArrayValues[startPos + i] = &args[i]; - - } else { - i = newI - 1; - } - } - } -} - -template -void LanguageMathML::printSparseArrayCreationOp(OperationNode& array) { - const std::vector& info = array.getInfo(); - CPPADCG_ASSERT_KNOWN(info.size() > 0, "Invalid number of information elements for sparse array creation operation"); - - const std::vector >& args = array.getArguments(); - const size_t argSize = args.size(); - - CPPADCG_ASSERT_KNOWN(info.size() == argSize + 1, "Invalid number of arguments for sparse array creation operation"); - - if (argSize == 0) - return; // empty array - - const size_t id = getVariableID(array); - size_t startPos = id - 1; - - bool firstElement = true; - for (size_t i = 0; i < argSize; i++) { - bool newValue = !isSameArgument(args[i], _tmpSparseArrayValues[startPos + i]); - - if (newValue) { - if (firstElement) { - _code << _startEq - << "" << auxArrayName_ << "" << _assignStr << _nameGen->generateTemporarySparseArray(array, getVariableID(array)) - << _endEq - << " " << _endline; - firstElement = false; - } - - // try to use a loop for element assignment - size_t newI = printArrayCreationUsingLoop(startPos, array, i, _tmpSparseArrayValues); - - // print element values not assign in a loop - if (newI == i) { - // individual element assignment - _code << _startEq - << "" << auxArrayName_ << "" << i << "" << _assignStr; - print(args[i]); - _code << _endEq; - _code << ", "; - // print indexes (location of values) - _code << _startEq - << "" << _C_SPARSE_INDEX_ARRAY << ""; - if (startPos != 0) _code << "" << startPos << "+"; - _code << "" << i << "" << _assignStr << "" << info[i + 1] << "" - << _endEq << _endline; - - _tmpSparseArrayValues[startPos + i] = &args[i]; - - } else { - // print indexes (location of values) - for (size_t j = i; j < newI; j++) { - _code << _startEq - << "" << _C_SPARSE_INDEX_ARRAY << ""; - if (startPos != 0) _code << "" << startPos << "+"; - _code << "" << j << "" << _assignStr << "" << info[j + 1] << "" - << _endEq << _endline; - } - - i = newI - 1; - } - - - } else { - // print indexes (location of values) - _code << _startEq - << "" << _C_SPARSE_INDEX_ARRAY << ""; - if (startPos != 0) _code << "" << startPos << "+"; - _code << "" << i << "" << _assignStr << "" << info[i + 1] << "" - << _endEq << _endline; - } - - } -} - -template -inline size_t LanguageMathML::printArrayCreationUsingLoop(size_t startPos, - OperationNode& array, - size_t starti, - std::vector*>& tmpArrayValues) { - const std::vector >& args = array.getArguments(); - const size_t argSize = args.size(); - size_t i = starti + 1; - - std::ostringstream arrayAssign; - - const Argument& ref = args[starti]; - if (ref.getOperation() != nullptr) { - // - const OperationNode& refOp = *ref.getOperation(); - if (refOp.getOperationType() == CGOpCode::Inv) { - /** - * from independents array - */ - for (; i < argSize; i++) { - if (isSameArgument(args[i], tmpArrayValues[startPos + i])) - break; // no assignment needed - - if (args[i].getOperation() == nullptr || - args[i].getOperation()->getOperationType() != CGOpCode::Inv || - !_nameGen->isConsecutiveInIndepArray(*args[i - 1].getOperation(), getVariableID(*args[i - 1].getOperation()), - *args[i].getOperation(), getVariableID(*args[i].getOperation()))) { - break; - } - } - - if (i - starti < 3) - return starti; - - // use loop - const std::string& indep = _nameGen->getIndependentArrayName(refOp, getVariableID(refOp)); - size_t start = _nameGen->getIndependentArrayIndex(refOp, getVariableID(refOp)); - long offset = long(start) - starti; - if (offset == 0) - arrayAssign << "" << indep << "" << "i"; - else - arrayAssign << "" << indep << "" << "" << offset << " + i"; - - } else if (refOp.getOperationType() == CGOpCode::LoopIndexedIndep) { - /** - * from independents array in a loop - */ - size_t pos = refOp.getInfo()[1]; - IndexPattern* refIp = _info->loopIndependentIndexPatterns[pos]; - if (refIp->getType() != IndexPatternType::Linear) { - return starti; // cannot determine consecutive elements - } - - LinearIndexPattern* refLIp = static_cast (refIp); - - for (; i < argSize; i++) { - if (isSameArgument(args[i], tmpArrayValues[startPos + i])) - break; // no assignment needed - - if (args[i].getOperation() == nullptr || - args[i].getOperation()->getOperationType() != CGOpCode::LoopIndexedIndep) { - break; // not an independent index pattern - } - - if (!_nameGen->isInSameIndependentArray(refOp, getVariableID(refOp), - *args[i].getOperation(), getVariableID(*args[i].getOperation()))) - break; - - pos = args[i].getOperation()->getInfo()[1]; - const IndexPattern* ip = _info->loopIndependentIndexPatterns[pos]; - if (ip->getType() != IndexPatternType::Linear) { - break; // different pattern type - } - const LinearIndexPattern* lIp = static_cast (ip); - if (refLIp->getLinearSlopeDx() != lIp->getLinearSlopeDx() || - refLIp->getLinearSlopeDy() != lIp->getLinearSlopeDy() || - refLIp->getXOffset() != lIp->getXOffset() || - refLIp->getLinearConstantTerm() - long(starti) != lIp->getLinearConstantTerm() - long(i)) { - break; - } - } - - if (i - starti < 3) - return starti; - - LinearIndexPattern* lip2 = new LinearIndexPattern(*refLIp); - lip2->setLinearConstantTerm(lip2->getLinearConstantTerm() - starti); - Plane2DIndexPattern p2dip(lip2, - new LinearIndexPattern(0, 1, 1, 0)); - - std::unique_ptr> op2(OperationNode::makeTemporaryNode(CGOpCode::LoopIndexedIndep, refOp.getInfo(), refOp.getArguments())); - op2->getInfo()[1] = std::numeric_limits::max(); // just to be safe (this would be the index pattern id in the handler) - op2->getArguments().push_back(_info->auxIterationIndexOp); - - arrayAssign << _nameGen->generateIndexedIndependent(*op2, 0, p2dip); - - } else { - // no loop used - return starti; - } - } else { - /** - * constant value? - */ - const Base& value = *args[starti].getParameter(); - for (; i < argSize; i++) { - if (args[i].getParameter() == nullptr || *args[i].getParameter() != value) { - break; // not the same constant value - } - - const Argument* oldArg = tmpArrayValues[startPos + i]; - if (oldArg != nullptr && oldArg->getParameter() != nullptr && *oldArg->getParameter() == value) { - break; // values are the same (no need to redefine) - } - } - - if (i - starti < 3) - return starti; - - arrayAssign << value; - } - - /** - * print the loop - */ - _code << _forStart << _startEq << "for" - "i" - "" - "" << starti << "" << i << "" - "" - "" << _endEq << _endline - << _forBodyStart; - _indentationLevel++; - _code << _startEq - << "" << auxArrayName_ << "i" << _assignStr << arrayAssign.str() - << _endEq << _endline; - _indentationLevel--; - _code << _forBodyEnd << _endline << _forEnd << _endline; - - /** - * update values in the global temporary array - */ - for (size_t ii = starti; ii < i; ii++) { - tmpArrayValues[startPos + ii] = &args[ii]; - } - - return i; -} - -template -inline std::string LanguageMathML::getTempArrayName(const OperationNode& op) { - if (op.getOperationType() == CGOpCode::ArrayCreation) - return _nameGen->generateTemporaryArray(op); - else - return _nameGen->generateTemporarySparseArray(op); -} - -template -void LanguageMathML::printArrayElementOp(OperationNode& op) { - CPPADCG_ASSERT_KNOWN(op.getArguments().size() == 2, "Invalid number of arguments for array element operation"); - CPPADCG_ASSERT_KNOWN(op.getArguments()[0].getOperation() != nullptr, "Invalid argument for array element operation"); - CPPADCG_ASSERT_KNOWN(op.getInfo().size() == 1, "Invalid number of information indexes for array element operation"); - - OperationNode& arrayOp = *op.getArguments()[0].getOperation(); - std::string arrayName; - if (arrayOp.getOperationType() == CGOpCode::ArrayCreation) - arrayName = _nameGen->generateTemporaryArray(arrayOp, getVariableID(arrayOp)); - else - arrayName = _nameGen->generateTemporarySparseArray(arrayOp, getVariableID(arrayOp)); - - _code << "(" << arrayName << ")" << op.getInfo()[0] << ""; -} - -template -inline void LanguageMathML::printArrayStructInit(const std::string& dataArrayName, - size_t pos, - const std::vector*>& arrays, - size_t k) { - _ss.str(""); - _ss << "" << dataArrayName << "" << pos << ""; - printArrayStructInit(_ss.str(), *arrays[k]); -} - -template -inline void LanguageMathML::printArrayStructInit(const std::string& dataArrayName, - OperationNode& array) { - /** - * TODO: finish this - */ - const std::string& aName = createVariableName(array); - - if (array.getOperationType() == CGOpCode::ArrayCreation) { - // dense array - size_t size = array.getArguments().size(); - if (size > 0) - _code << dataArrayName << ".data=" << aName; - else - _code << dataArrayName << ".data=NULL"; - _code << dataArrayName << ".size=" << size << "" - << dataArrayName << ".sparse=" << false << ""; - } else { - // sparse array - CPPADCG_ASSERT_KNOWN(array.getOperationType() == CGOpCode::SparseArrayCreation, "Invalid node type"); - size_t nnz = array.getArguments().size(); - if (nnz > 0) - _code << dataArrayName << ".data=" << aName; - else - _code << dataArrayName << ".data=NULL"; - _code << dataArrayName << ".size=" << array.getInfo()[0] << "" - << dataArrayName << ".sparse=" << true << "" - << dataArrayName << ".nnz=" << nnz << ""; - if (nnz > 0) { - size_t id = getVariableID(array); - _code << dataArrayName << ".idx=&(" << _C_SPARSE_INDEX_ARRAY << "" << (id - 1) << ")"; - } - } - _code << _endline; -} - -template -inline void LanguageMathML::markArrayChanged(OperationNode& ty) { - size_t id = getVariableID(ty); - size_t tySize = ty.getArguments().size(); - - if (ty.getOperationType() == CGOpCode::ArrayCreation) { - for (size_t i = 0; i < tySize; i++) { - _tmpArrayValues[id - 1 + i] = nullptr; - } - } else { - for (size_t i = 0; i < tySize; i++) { - _tmpSparseArrayValues[id - 1 + i] = nullptr; - } - } -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/mathml/language_mathml_index_patterns.hpp b/ct_core/include/ct/external/cppad/cg/lang/mathml/language_mathml_index_patterns.hpp deleted file mode 100644 index 5e56c9bb1..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/mathml/language_mathml_index_patterns.hpp +++ /dev/null @@ -1,275 +0,0 @@ -#ifndef CPPAD_CG_LANGUAGE_MATHML_INDEX_PATTERNS_INCLUDED -#define CPPAD_CG_LANGUAGE_MATHML_INDEX_PATTERNS_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2015 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -inline void LanguageMathML::generateNames4RandomIndexPatterns(const std::set& randomPatterns) { - std::ostringstream os; - - std::set usedNames; - - // save existing names so that they are not to overridden - // (independent variable names might have already used them) - for (RandomIndexPattern* ip : randomPatterns) { - if (!ip->getName().empty()) { - usedNames.insert(ip->getName()); - } - } - - // create new names for the index pattern arrays without a name - size_t c = 0; - for (RandomIndexPattern* ip : randomPatterns) { - if (ip->getName().empty()) { - // new name required - std::string name; - do { - os << _C_STATIC_INDEX_ARRAY << c; - name = os.str(); - os.str(""); - c++; - } while (usedNames.find(name) != usedNames.end()); - - ip->setName("" + name + ""); - } - } - -} - -template -inline void LanguageMathML::printRandomIndexPatternDeclaration(std::ostringstream& os, - const std::string& indentation, - const std::set& randomPatterns) { - for (RandomIndexPattern* ip : randomPatterns) { - if (ip->getType() == IndexPatternType::Random1D) { - /** - * 1D - */ - Random1DIndexPattern* ip1 = static_cast (ip); - const std::map& x2y = ip1->getValues(); - - std::vector y(x2y.rbegin()->first + 1); - for (const std::pair& p : x2y) - y[p.first] = p.second; - - os << indentation; - printStaticIndexArray(os, ip->getName(), y); - } else { - CPPADCG_ASSERT_UNKNOWN(ip->getType() == IndexPatternType::Random2D); - /** - * 2D - */ - Random2DIndexPattern* ip2 = static_cast (ip); - os << indentation; - printStaticIndexMatrix(os, ip->getName(), ip2->getValues()); - } - } -} - -template -void LanguageMathML::printStaticIndexArray(std::ostringstream& os, - const std::string& name, - const std::vector& values) { - os << name << " = "; - for (size_t i = 0; i < values.size(); i++) { - os << "" << values[i] << ""; - } - os << "" << _endEq << " " << _endline; -} - -template -void LanguageMathML::printStaticIndexMatrix(std::ostringstream& os, - const std::string& name, - const std::map >& values) { - /** - * TODO - */ - size_t m = 0; - size_t n = 0; - - std::map >::const_iterator it; - std::map::const_iterator ity2z; - - if (!values.empty()) { - m = values.rbegin()->first + 1; - - for (it = values.begin(); it != values.end(); ++it) { - if (!it->second.empty()) - n = std::max(n, it->second.rbegin()->first + 1); - } - } - - os << name << "="; - size_t x = 0; - for (it = values.begin(); it != values.end(); ++it) { - if (it->first != x) { - while (it->first != x) { - os << ""; - x++; - } - } - - os << ""; - size_t y = 0; - for (ity2z = it->second.begin(); ity2z != it->second.end(); ++ity2z) { - if (ity2z->first != y) { - while (ity2z->first != y) { - os << "0"; - y++; - } - } - - os << "" << ity2z->second << ""; - - - y++; - } - os << ""; - - x++; - } - os << "" << _endEq << "" << _endline; -} - -template -inline void LanguageMathML::indexPattern2String(std::ostream& os, - const IndexPattern& ip, - const OperationNode& index) { - indexPattern2String(os, ip,{&index}); -} - -template -inline void LanguageMathML::indexPattern2String(std::ostream& os, - const IndexPattern& ip, - const std::vector*>& indexes) { - std::stringstream ss; - switch (ip.getType()) { - case IndexPatternType::Linear: // y = x * a + b - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 1, "Invalid number of indexes"); - const LinearIndexPattern& lip = static_cast (ip); - linearIndexPattern2String(os, lip, *indexes[0]); - return; - } - case IndexPatternType::Sectioned: - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 1, "Invalid number of indexes"); - const SectionedIndexPattern* lip = static_cast (&ip); - const std::map& sections = lip->getLinearSections(); - size_t sSize = sections.size(); - CPPADCG_ASSERT_UNKNOWN(sSize > 1); - - std::map::const_iterator its = sections.begin(); - for (size_t s = 0; s < sSize - 1; s++) { - const IndexPattern* lp = its->second; - ++its; - size_t xStart = its->first; - - os << "" << (*indexes[0]->getName()) << " < " << xStart << "? "; - indexPattern2String(os, *lp, *indexes[0]); - os << ": "; - } - indexPattern2String(os, *its->second, *indexes[0]); - - return; - } - - case IndexPatternType::Plane2D: // y = f(x) + f(z) - { - CPPADCG_ASSERT_KNOWN(indexes.size() >= 1, "Invalid number of indexes"); - const Plane2DIndexPattern& pip = static_cast (ip); - bool useParens = pip.getPattern1() != nullptr && pip.getPattern2() != nullptr; - - if (useParens) os << ""; - - if (pip.getPattern1() != nullptr) - indexPattern2String(os, *pip.getPattern1(), *indexes[0]); - - if (useParens) os << " + "; - - if (pip.getPattern2() != nullptr) - indexPattern2String(os, *pip.getPattern2(), *indexes.back()); - - if (useParens) os << ""; - - return; - } - case IndexPatternType::Random1D: - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 1, "Invalid number of indexes"); - const Random1DIndexPattern& rip = static_cast (ip); - CPPADCG_ASSERT_KNOWN(!rip.getName().empty(), "Invalid name for array"); - os << rip.getName() << "" << (*indexes[0]->getName()) << ""; - return; - } - case IndexPatternType::Random2D: - { - CPPADCG_ASSERT_KNOWN(indexes.size() == 2, "Invalid number of indexes"); - const Random2DIndexPattern& rip = static_cast (ip); - CPPADCG_ASSERT_KNOWN(!rip.getName().empty(), "Invalid name for array"); - os << rip.getName() << - "" << (*indexes[0]->getName()) << "" - "" << (*indexes[1]->getName()) << ""; - return; - } - default: - CPPADCG_ASSERT_UNKNOWN(false); // should never reach this - return; - } -} - -template -inline void LanguageMathML::linearIndexPattern2String(std::ostream& os, - const LinearIndexPattern& lip, - const OperationNode& index) { - long dy = lip.getLinearSlopeDy(); - long dx = lip.getLinearSlopeDx(); - long b = lip.getLinearConstantTerm(); - long xOffset = lip.getXOffset(); - - if (dy != 0) { - if (xOffset != 0) { - os << ""; - } - os << "" << (*index.getName()) << ""; - if (xOffset != 0) { - os << " -" << xOffset << ""; - } - - if (dx != 1) { - os << "/" << dx << ""; - } - if (dy != 1) { - os << "\\times" << dy << ""; - } - } else if (b == 0) { - os << "0"; // when dy == 0 and b == 0 - } - - if (b != 0) { - if (dy != 0) - os << "+"; - os << "" << b << ""; - } - -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/lang/mathml/mathml.hpp b/ct_core/include/ct/external/cppad/cg/lang/mathml/mathml.hpp deleted file mode 100644 index a4e82a781..000000000 --- a/ct_core/include/ct/external/cppad/cg/lang/mathml/mathml.hpp +++ /dev/null @@ -1,26 +0,0 @@ -#ifndef CPPAD_CG_MATHML_INCLUDED -#define CPPAD_CG_MATHML_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2015 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -// --------------------------------------------------------------------------- -// mathml source code generation -#include -#include -#include -#include -#include - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/math.hpp b/ct_core/include/ct/external/cppad/cg/math.hpp deleted file mode 100644 index ce1d4b073..000000000 --- a/ct_core/include/ct/external/cppad/cg/math.hpp +++ /dev/null @@ -1,67 +0,0 @@ -#ifndef CPPAD_CG_MATH_INCLUDED -#define CPPAD_CG_MATH_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { - -#define CPPAD_CG_CREATE_OPERATION(OpName, OpCode) \ - template \ - inline cg::CG OpName(const cg::CG& var) { \ - using namespace CppAD::cg; \ - if (var.isParameter()) { \ - return CG (OpName(var.getValue())); \ - } else { \ - CodeHandler& h = *var.getOperationNode()->getCodeHandler(); \ - CG result(*h.makeNode(CGOpCode::OpCode, var.argument())); \ - if(var.isValueDefined()) \ - result.setValue(OpName(var.getValue())); \ - return result; \ - } \ - } - -CPPAD_CG_CREATE_OPERATION(abs, Abs) -CPPAD_CG_CREATE_OPERATION(fabs, Abs) -CPPAD_CG_CREATE_OPERATION(acos, Acos) -CPPAD_CG_CREATE_OPERATION(asin, Asin) -CPPAD_CG_CREATE_OPERATION(atan, Atan) -CPPAD_CG_CREATE_OPERATION(cos, Cos) -CPPAD_CG_CREATE_OPERATION(cosh, Cosh) -CPPAD_CG_CREATE_OPERATION(exp, Exp) -CPPAD_CG_CREATE_OPERATION(log, Log) -CPPAD_CG_CREATE_OPERATION(sin, Sin) -CPPAD_CG_CREATE_OPERATION(sinh, Sinh) -CPPAD_CG_CREATE_OPERATION(sqrt, Sqrt) -CPPAD_CG_CREATE_OPERATION(tan, Tan) -CPPAD_CG_CREATE_OPERATION(tanh, Tanh) - -#if CPPAD_USE_CPLUSPLUS_2011 -// c++11 functions -CPPAD_CG_CREATE_OPERATION(erf, Erf) -CPPAD_CG_CREATE_OPERATION(asinh, Asinh) -CPPAD_CG_CREATE_OPERATION(acosh, Acosh) -CPPAD_CG_CREATE_OPERATION(atanh, Atanh) -CPPAD_CG_CREATE_OPERATION(expm1, Expm1) -CPPAD_CG_CREATE_OPERATION(log1p, Log1p) -#endif - -template -inline cg::CG log10(const cg::CG &x) { - return CppAD::log(x) / CppAD::log(Base(10)); -} - -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/math_other.hpp b/ct_core/include/ct/external/cppad/cg/math_other.hpp deleted file mode 100644 index 6c9d90ca0..000000000 --- a/ct_core/include/ct/external/cppad/cg/math_other.hpp +++ /dev/null @@ -1,103 +0,0 @@ -#ifndef CPPAD_CG_MATH_OTHER_INCLUDED -#define CPPAD_CG_MATH_OTHER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { - -template -inline CppAD::cg::CG pow(const CppAD::cg::CG& x, - const CppAD::cg::CG& y) { - using namespace CppAD::cg; - - if (x.isParameter() && y.isParameter()) { - return CG (pow(x.getValue(), y.getValue())); - } - - CodeHandler* handler; - if (y.isParameter()) { - if (y.isIdenticalZero()) { - return CG (Base(1.0)); // does not consider that x could be infinity - } else if (y.isIdenticalOne()) { - return CG (x); - } - handler = x.getCodeHandler(); - } else { - handler = y.getCodeHandler(); - } - - CG result(*handler->makeNode(CGOpCode::Pow,{x.argument(), y.argument()})); - if (x.isValueDefined() && y.isValueDefined()) { - result.setValue(pow(x.getValue(), y.getValue())); - } - return result; -} - -/******************************************************************************* - * pow() with other types - ******************************************************************************/ - -template -inline CppAD::cg::CG pow(const Base& x, - const CppAD::cg::CG& y) { - return CppAD::pow(CppAD::cg::CG(x), y); -} - -template -inline CppAD::cg::CG pow(const CppAD::cg::CG& x, - const Base& y) { - return CppAD::pow(x, CppAD::cg::CG(y)); -} - -template -CppAD::cg::CG pow(const int& x, - const CppAD::cg::CG& y) { - return pow(CppAD::cg::CG(x), y); -} - -/******************************************************************************* - * - ******************************************************************************/ -template -inline CppAD::cg::CG sign(const CppAD::cg::CG& x) { - using namespace CppAD::cg; - - if (x.isParameter()) { - if (x.getValue() > Base(0.0)) { - return CG (Base(1.0)); - } else if (x.getValue() == Base(0.0)) { - return CG (Base(0.0)); - } else { - return CG (Base(-1.0)); - } - } - - CodeHandler& h = *x.getOperationNode()->getCodeHandler(); - CG result(*h.makeNode(CGOpCode::Sign, x.argument())); - if (x.isValueDefined()) { - if (x.getValue() > Base(0.0)) { - result.setValue(Base(1.0)); - } else if (x.getValue() == Base(0.0)) { - result.setValue(Base(0.0)); - } else { - result.setValue(Base(-1.0)); - } - } - return result; -} - -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/atomic_external_function_wrapper.hpp b/ct_core/include/ct/external/cppad/cg/model/atomic_external_function_wrapper.hpp deleted file mode 100644 index 9218f863a..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/atomic_external_function_wrapper.hpp +++ /dev/null @@ -1,154 +0,0 @@ -#ifndef CPPAD_CG_ATOMIC_EXTERNAL_FUNCTION_INCLUDED -#define CPPAD_CG_ATOMIC_EXTERNAL_FUNCTION_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -class AtomicExternalFunctionWrapper : public ExternalFunctionWrapper { -private: - atomic_base* atomic_; -public: - - inline AtomicExternalFunctionWrapper(atomic_base& atomic) : - atomic_(&atomic) { - } - - virtual bool forward(FunctorGenericModel& libModel, - int q, - int p, - const Array tx[], - Array& ty) override { - size_t m = ty.size; - size_t n = tx[0].size; - - CppAD::vector vx, vy; - - convert(tx, libModel._tx, n, p, p + 1); - - size_t ty_size = m * (p + 1); - if (libModel._ty.size() < ty_size) { - libModel._ty.resize(ty_size); - } - std::fill(&libModel._ty[0], &libModel._ty[0] + ty_size, Base(0)); - - bool ret = atomic_->forward(q, p, vx, vy, libModel._tx, libModel._ty); - - convertAdd(libModel._ty, ty, m, p, p); - - return ret; - } - - virtual bool reverse(FunctorGenericModel& libModel, - int p, - const Array tx[], - Array& px, - const Array py[]) override { - size_t m = py[0].size; - size_t n = tx[0].size; - - convert(tx, libModel._tx, n, p, p + 1); - - libModel._ty.resize(m * (p + 1)); - std::fill(&libModel._ty[0], &libModel._ty[0] + libModel._ty.size(), Base(0)); - - convert(py, libModel._py, m, p, p + 1); - - size_t px_size = n * (p + 1); - if (libModel._px.size() < px_size) { - libModel._px.resize(px_size); - } - std::fill(&libModel._px[0], &libModel._px[0] + px_size, Base(0)); - -#ifndef NDEBUG - if (libModel._evalAtomicForwardOne4CppAD) { - // only required in order to avoid an issue with a validation inside CppAD - CppAD::vector vx, vy; - if (!atomic_->forward(p, p, vx, vy, libModel._tx, libModel._ty)) - return false; - } -#endif - - bool ret = atomic_->reverse(p, libModel._tx, libModel._ty, libModel._px, libModel._py); - - convertAdd(libModel._px, px, n, p, 0); // k=0 for both p=0 and p=1 - - return ret; - } - - inline virtual ~AtomicExternalFunctionWrapper() { - } -private: - - inline void convert(const Array from[], - CppAD::vector& to, - size_t n, - size_t p, - size_t kmax) { - size_t p1 = p + 1; - to.resize(n * p1); - - for (size_t k = 0; k < kmax; k++) { - Base* values = static_cast (from[k].data); - if (from[k].sparse) { - if (p == 0) { - std::fill(&to[0], &to[0] + n, Base(0)); - } else { - for (size_t j = 0; j < n; j++) { - to[j * p1 + k] = Base(0); - } - } - - for (size_t e = 0; e < from[k].nnz; e++) { - size_t j = from[k].idx[e]; - to[j * p1 + k] = values[e]; - } - } else { - for (size_t j = 0; j < n; j++) { - to[j * p1 + k] = values[j]; - } - } - } - } - - inline void convertAdd(const CppAD::vector& from, - Array& to, - size_t n, - size_t p, - size_t k) { - CPPADCG_ASSERT_KNOWN(!to.sparse, "output must be a dense array"); - CPPADCG_ASSERT_KNOWN(to.size >= n, "invalid size"); - - Base* values = static_cast (to.data); - - if (p == 0) { - std::copy(&from[0], &from[0] + n, values); - } else { - size_t p1 = p + 1; - - for (size_t j = 0; j < n; j++) { - values[j] += from[j * p1 + k]; - } - } - - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/atomic_generic_model.hpp b/ct_core/include/ct/external/cppad/cg/model/atomic_generic_model.hpp deleted file mode 100644 index e08c93414..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/atomic_generic_model.hpp +++ /dev/null @@ -1,181 +0,0 @@ -#ifndef CPPAD_CG_ATOMIC_GENERIC_MODEL_INCLUDED -#define CPPAD_CG_ATOMIC_GENERIC_MODEL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * An atomic function that uses a compiled model - * - * @author Joao Leal - */ -template -class CGAtomicGenericModel : public atomic_base { -protected: - GenericModel& model_; -public: - - /** - * Creates a new atomic function wrapper that is responsible for - * calling the appropriate methods of the compiled model. - * - * @param model The compiled model. - */ - CGAtomicGenericModel(GenericModel& model) : - atomic_base(model.getName()), - model_(model) { - this->option(CppAD::atomic_base::set_sparsity_enum); - } - - template - void operator()(const ADVector& ax, ADVector& ay, size_t id = 0) { - this->atomic_base::operator()(ax, ay, id); - } - - virtual bool forward(size_t q, - size_t p, - const CppAD::vector& vx, - CppAD::vector& vy, - const CppAD::vector& tx, - CppAD::vector& ty) override { - if (p == 0) { - model_.ForwardZero(vx, vy, tx, ty); - return true; - } else if (p == 1) { - model_.ForwardOne(tx, ty); - return true; - } - - return false; - } - - virtual bool reverse(size_t p, - const CppAD::vector& tx, - const CppAD::vector& ty, - CppAD::vector& px, - const CppAD::vector& py) override { - if (p == 0) { - model_.ReverseOne(tx, ty, px, py); - return true; - } else if (p == 1) { - model_.ReverseTwo(tx, ty, px, py); - return true; - } - - return false; - } - - virtual bool for_sparse_jac(size_t q, - const CppAD::vector >& r, - CppAD::vector >& s) override { - size_t n = model_.Domain(); - size_t m = model_.Range(); - for (size_t i = 0; i < m; i++) { - s[i].clear(); - } - - const std::vector > jacSparsity = model_.JacobianSparsitySet(); - CppAD::cg::multMatrixMatrixSparsity(jacSparsity, r, s, m, n, q); - - return true; - } - - virtual bool rev_sparse_jac(size_t q, - const CppAD::vector >& rT, - CppAD::vector >& sT) override { - size_t n = model_.Domain(); - size_t m = model_.Range(); - for (size_t i = 0; i < n; i++) { - sT[i].clear(); - } - - const std::vector > jacSparsity = model_.JacobianSparsitySet(); - - CppAD::cg::multMatrixMatrixSparsityTrans(rT, jacSparsity, sT, m, n, q); - - return true; - } - - virtual bool rev_sparse_hes(const CppAD::vector& vx, - const CppAD::vector& s, - CppAD::vector& t, - size_t q, - const CppAD::vector >& r, - const CppAD::vector >& u, - CppAD::vector >& v) override { - size_t n = model_.Domain(); - size_t m = model_.Range(); - - for (size_t i = 0; i < n; i++) { - v[i].clear(); - } - - const std::vector > jacSparsity = model_.JacobianSparsitySet(); - - /** - * V(x) = f'^T(x) U(x) + Sum( s(x)i f''(x) R(x) ) - */ - // f'^T(x) U(x) - CppAD::cg::multMatrixTransMatrixSparsity(jacSparsity, u, v, m, n, q); - - // Sum( s(x)i f''(x) R(x) ) - bool allSelected = true; - for (size_t i = 0; i < m; i++) { - if (!s[i]) { - allSelected = false; - break; - } - } - - if (allSelected) { - // TODO: use reverseTwo sparsity instead of the HessianSparsity (they can be different!!!) - std::vector > sparsitySF2R = model_.HessianSparsitySet(); // f''(x) - sparsitySF2R.resize(n); - CppAD::cg::multMatrixTransMatrixSparsity(sparsitySF2R, r, v, n, n, q); // f''^T * R - } else { - std::vector > sparsitySF2R(n); - for (size_t i = 0; i < m; i++) { - if (s[i]) { - CppAD::cg::addMatrixSparsity(model_.HessianSparsitySet(i), sparsitySF2R); // f''_i(x) - } - } - CppAD::cg::multMatrixTransMatrixSparsity(sparsitySF2R, r, v, n, n, q); // f''^T * R - } - - /** - * S(x) * f'(x) - */ - for (size_t i = 0; i < m; i++) { - if (s[i]) { - for (size_t j : jacSparsity[i]) { - t[j] = true; - } - } - } - - return true; - } - - virtual ~CGAtomicGenericModel() { - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/compiler/abstract_c_compiler.hpp b/ct_core/include/ct/external/cppad/cg/model/compiler/abstract_c_compiler.hpp deleted file mode 100644 index 8746e1ab3..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/compiler/abstract_c_compiler.hpp +++ /dev/null @@ -1,295 +0,0 @@ -#ifndef CPPAD_CG_ABSTRACT_C_COMPILER_INCLUDED -#define CPPAD_CG_ABSTRACT_C_COMPILER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Default implementation of a C compiler class used to create - * dynamic and static libraries - * - * @author Joao Leal - */ -template -class AbstractCCompiler : public CCompiler { -protected: - std::string _path; // the path to the gcc executable - std::string _tmpFolder; - std::string _sourcesFolder; // path where source files are save - std::set _ofiles; // compiled object files - std::set _sfiles; // compiled source files - std::vector _compileFlags; - std::vector _compileLibFlags; - std::vector _linkFlags; - bool _verbose; - bool _saveToDiskFirst; -public: - - AbstractCCompiler(const std::string& compilerPath) : - _path(compilerPath), - _tmpFolder("cppadcg_tmp"), - _sourcesFolder("cppadcg_sources"), - _verbose(false), - _saveToDiskFirst(false) { - } - - AbstractCCompiler(const AbstractCCompiler& orig) = delete; - AbstractCCompiler& operator=(const AbstractCCompiler& rhs) = delete; - - std::string getCompilerPath() const { - return _path; - } - - void setCompilerPath(const std::string& path) { - _path = path; - } - - virtual const std::string& getTemporaryFolder() const override { - return _tmpFolder; - } - - virtual void setTemporaryFolder(const std::string& tmpFolder) override { - _tmpFolder = tmpFolder; - } - - virtual bool isSaveToDiskFirst() const override { - return _saveToDiskFirst; - } - - virtual void setSaveToDiskFirst(bool saveToDiskFirst) override { - _saveToDiskFirst = saveToDiskFirst; - } - - virtual const std::string& getSourcesFolder() const override { - return _sourcesFolder; - } - - virtual void setSourcesFolder(const std::string& srcFolder) override { - _sourcesFolder = srcFolder; - } - - virtual const std::set& getObjectFiles() const override { - return _ofiles; - } - - virtual const std::set& getSourceFiles() const override { - return _sfiles; - } - - const std::vector& getCompileFlags() const { - return _compileFlags; - } - - void setCompileFlags(const std::vector& compileFlags) { - _compileFlags = compileFlags; - } - - void addCompileFlag(const std::string& compileFlag) { - _compileFlags.push_back(compileFlag); - } - - const std::vector& getLinkFlags() const { - return _linkFlags; - } - - void setLinkFlags(const std::vector& linkFlags) { - _linkFlags = linkFlags; - } - - void addLinkFlag(const std::string& linkFlag) { - _linkFlags.push_back(linkFlag); - } - - const std::vector& getCompileLibFlags() const { - return _compileLibFlags; - } - - void setCompileLibFlags(const std::vector& compileLibFlags) { - _compileLibFlags = compileLibFlags; - } - - void addCompileLibFlag(const std::string& compileLibFlag) { - _compileLibFlags.push_back(compileLibFlag); - } - - virtual bool isVerbose() const override { - return _verbose; - } - - virtual void setVerbose(bool verbose) override { - _verbose = verbose; - } - - /** - * Compiles the provided C source code. - * - * @param library the path of the dynamic library to be created - * @param sources maps the names to the content of the source files - * @param posIndepCode whether or not to create position-independent - * code for dynamic linking - */ - virtual void compileSources(const std::map& sources, - bool posIndepCode, - JobTimer* timer = nullptr) override { - compileSources(sources, posIndepCode, timer, ".o", _ofiles); - } - - virtual void compileSources(const std::map& sources, - bool posIndepCode, - JobTimer* timer, - const std::string& outputExtension, - std::set& outputFiles) { - using namespace std::chrono; - - if (sources.empty()) - return; // nothing to do - - system::createFolder(this->_tmpFolder); - - // determine the maximum file name length - size_t maxsize = 0; - std::map::const_iterator it; - for (it = sources.begin(); it != sources.end(); ++it) { - _sfiles.insert(it->first); - std::string file = system::createPath(this->_tmpFolder, it->first + outputExtension); - maxsize = std::max(maxsize, file.size()); - } - - size_t countWidth = std::ceil(std::log10(sources.size())); - - size_t count = 0; - if (timer != nullptr) { - size_t ms = 3 + 2 * countWidth + 1 + JobTypeHolder<>::COMPILING.getActionName().size() + 2 + maxsize + 5; - ms += timer->getJobCount() * 2; - if (timer->getMaxLineWidth() < ms) - timer->setMaxLineWidth(ms); - } else if (_verbose) { - std::cout << std::endl; - } - - std::ostringstream os; - - if (_saveToDiskFirst) { - system::createFolder(_sourcesFolder); - } - - // compile each source code file into a different object file - for (it = sources.begin(); it != sources.end(); ++it) { - count++; - std::string file = system::createPath(this->_tmpFolder, it->first + outputExtension); - outputFiles.insert(file); - - steady_clock::time_point beginTime; - - if (timer != nullptr || _verbose) { - os << "[" << std::setw(countWidth) << std::setfill(' ') << std::right << count - << "/" << sources.size() << "]"; - } - - if (timer != nullptr) { - timer->startingJob("'" + file + "'", JobTypeHolder<>::COMPILING, os.str()); - os.str(""); - } else if (_verbose) { - beginTime = steady_clock::now(); - char f = std::cout.fill(); - std::cout << os.str() << " compiling " - << std::setw(maxsize + 9) << std::setfill('.') << std::left - << ("'" + file + "' ") << " "; - os.str(""); - std::cout.flush(); - std::cout.fill(f); // restore fill character - } - - if (_saveToDiskFirst) { - // save a new source file to disk - std::ofstream sourceFile; - std::string srcfile = system::createPath(_sourcesFolder, it->first); - sourceFile.open(srcfile.c_str()); - sourceFile << it->second; - sourceFile.close(); - - // compile the file - compileFile(srcfile, file, posIndepCode); - } else { - // compile without saving the source code to disk - compileSource(it->second, file, posIndepCode); - } - - if (timer != nullptr) { - timer->finishedJob(); - } else if (_verbose) { - steady_clock::time_point endTime = steady_clock::now(); - duration dt = endTime - beginTime; - std::cout << "done [" << std::fixed << std::setprecision(3) - << dt.count() << "]" << std::endl; - } - - } - - } - - /** - * Creates a dynamic library from a set of object files - * - * @param library the path to the dynamic library to be created - */ - virtual void buildDynamic(const std::string& library, - JobTimer* timer = nullptr) override = 0; - - virtual void cleanup() override { - // clean up; - for (const std::string& it : _ofiles) { - if (remove(it.c_str()) != 0) - std::cerr << "Failed to delete temporary file '" << it << "'" << std::endl; - } - _ofiles.clear(); - _sfiles.clear(); - - remove(this->_tmpFolder.c_str()); - } - - virtual ~AbstractCCompiler() { - cleanup(); - } - -protected: - - /** - * Compiles a single source file into an object file. - * - * @param source the content of the source file - * @param output the compiled output file name (the object file path) - */ - virtual void compileSource(const std::string& source, - const std::string& output, - bool posIndepCode) = 0; - - /** - * Compiles a single source file into an object file. - * - * @param path the path to the source file - * @param output the compiled output file name (the object file path) - */ - virtual void compileFile(const std::string& path, - const std::string& output, - bool posIndepCode) = 0; -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/compiler/c_compiler.hpp b/ct_core/include/ct/external/cppad/cg/model/compiler/c_compiler.hpp deleted file mode 100644 index 91cae1026..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/compiler/c_compiler.hpp +++ /dev/null @@ -1,107 +0,0 @@ -#ifndef CPPAD_CG_C_COMPILER_INCLUDED -#define CPPAD_CG_C_COMPILER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * C compiler class used to create a dynamic library - * - * @author Joao Leal - */ -template -class CCompiler { -public: - - /** - * Provides the path to a temporary folder that should not exist - * (it will be deleted after the dynamic library is created) - * - * @return path to a temporary folder. - */ - virtual const std::string& getTemporaryFolder() const = 0; - - /** - * Defines the path to a temporary folder that should not exist - * (it will be deleted after the dynamic library is created) - * - * @param tmpFolder path to a temporary folder. - */ - virtual void setTemporaryFolder(const std::string& tmpFolder) = 0; - - virtual bool isSaveToDiskFirst() const = 0; - - virtual void setSaveToDiskFirst(bool saveToDiskFirst) = 0; - - /** - * Provides the path to a folder where the source files should be created - * when the option to save files to disk is active. - * - * @return path to a folder. - */ - virtual const std::string& getSourcesFolder() const = 0; - - /** - * Defines the path to a folder where the source files should be created - * when the option to save files to disk is active. - * - * @param srcFolder path to the folder. - */ - virtual void setSourcesFolder(const std::string& srcFolder) = 0; - - virtual const std::set& getObjectFiles() const = 0; - - virtual const std::set& getSourceFiles() const = 0; - - virtual bool isVerbose() const = 0; - - virtual void setVerbose(bool verbose) = 0; - - /** - * Compiles the provided C source code. - * - * @param sources maps the names to the content of the source files - * @param posIndepCode whether or not to create position-independent - * code for dynamic linking - */ - virtual void compileSources(const std::map& sources, - bool posIndepCode, - JobTimer* timer = nullptr) = 0; - - /** - * Creates a dynamic library from the previously compiled object files - * - * @param library the path to the dynamic library to be created - */ - virtual void buildDynamic(const std::string& library, - JobTimer* timer = nullptr) = 0; - - /** - * Deletes the previously compiled object files and clears of files - * to include in a dynamic library - */ - virtual void cleanup() = 0; - - inline virtual ~CCompiler() { - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/compiler/clang_compiler.hpp b/ct_core/include/ct/external/cppad/cg/model/compiler/clang_compiler.hpp deleted file mode 100644 index fa1d9d4f8..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/compiler/clang_compiler.hpp +++ /dev/null @@ -1,196 +0,0 @@ -#ifndef CPPAD_CG_CLANG_COMPILER_INCLUDED -#define CPPAD_CG_CLANG_COMPILER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Clang compiler - * - * @author Joao Leal - */ -template -class ClangCompiler : public AbstractCCompiler { -protected: - std::set _bcfiles; // bitcode files - std::string _version; -public: - - ClangCompiler(const std::string& clangPath = "/usr/bin/clang") : - AbstractCCompiler(clangPath) { - - this->_compileFlags.push_back("-O2"); // Optimization level - this->_compileLibFlags.push_back("-O2"); // Optimization level - this->_compileLibFlags.push_back("-shared"); // Make shared object - this->_compileLibFlags.push_back("-rdynamic"); // add all symbols to the dynamic symbol table - } - - ClangCompiler(const ClangCompiler& orig) = delete; - ClangCompiler& operator=(const ClangCompiler& rhs) = delete; - - const std::string& getVersion() { - if(_version.empty()) { - std::vector args {"--version"}; - std::string output; - system::callExecutable(this->_path, args, &output); - - std::string vv = "version "; - size_t is = output.find(vv); - if(is == std::string::npos) { - throw CGException("Failed to determine Clang version"); - } - is += vv.size(); - size_t i = is; - while (i < output.size() && output[i] != ' ' && output[i] != '\n') { - i++; - } - - _version = output.substr(is, i - is); - } - return _version; - } - - virtual const std::set& getBitCodeFiles() const { - return _bcfiles; - } - - virtual void generateLLVMBitCode(const std::map& sources, - JobTimer* timer = nullptr) { - bool posIndepCode = false; - this->_compileFlags.push_back("-emit-llvm"); - try { - this->compileSources(sources, posIndepCode, timer, ".bc", this->_bcfiles); - } catch (...) { - this->_compileFlags.pop_back(); - throw; - } - } - - /** - * Creates a dynamic library from a set of object files - * - * @param library the path to the dynamic library to be created - */ - virtual void buildDynamic(const std::string& library, - JobTimer* timer = nullptr) override { - - std::string linkerFlags = "-Wl,-soname," + system::filenameFromPath(library); - for (size_t i = 0; i < this->_linkFlags.size(); i++) - linkerFlags += "," + this->_linkFlags[i]; - - std::vector args; - args.insert(args.end(), this->_compileLibFlags.begin(), this->_compileLibFlags.end()); - args.push_back(linkerFlags); // Pass suitable options to linker - args.push_back("-o"); // Output file name - args.push_back(library); // Output file name - - for (const std::string& it : this->_ofiles) { - args.push_back(it); - } - - if (timer != nullptr) { - timer->startingJob("'" + library + "'", JobTimer::COMPILING_DYNAMIC_LIBRARY); - } else if (this->_verbose) { - std::cout << "building library '" << library << "'" << std::endl; - } - - system::callExecutable(this->_path, args); - - if (timer != nullptr) { - timer->finishedJob(); - } - } - - virtual void cleanup() override { - // clean up - for (const std::string& it : _bcfiles) { - if (remove(it.c_str()) != 0) - std::cerr << "Failed to delete temporary file '" << it << "'" << std::endl; - } - _bcfiles.clear(); - - // other files and temporary folder - AbstractCCompiler::cleanup(); - } - - virtual ~ClangCompiler() { - cleanup(); - } - - static std::vector parseVersion(const std::string& version) { - auto vv = explode(version, "."); - if (vv.size() > 2) { - auto vv2 = explode(vv[2], "-"); - if (vv2.size() > 1) { - vv.erase(vv.begin() + 2); - vv.insert(vv.begin() + 2, vv2.begin(), vv2.end()); - } - } - return vv; - } - -protected: - - /** - * Compiles a single source file into an output file - * (e.g. object file or bit code file) - * - * @param source the content of the source file - * @param output the compiled output file name (the object file path) - */ - virtual void compileSource(const std::string& source, - const std::string& output, - bool posIndepCode) override { - std::vector args; - args.push_back("-x"); - args.push_back("c"); // C source files - args.insert(args.end(), this->_compileFlags.begin(), this->_compileFlags.end()); - args.push_back("-c"); - args.push_back("-"); - if (posIndepCode) { - args.push_back("-fPIC"); // position-independent code for dynamic linking - } - args.push_back("-o"); - args.push_back(output); - - system::callExecutable(this->_path, args, nullptr, &source); - } - - virtual void compileFile(const std::string& path, - const std::string& output, - bool posIndepCode) override { - std::vector args; - args.push_back("-x"); - args.push_back("c"); // C source files - args.insert(args.end(), this->_compileFlags.begin(), this->_compileFlags.end()); - if (posIndepCode) { - args.push_back("-fPIC"); // position-independent code for dynamic linking - } - args.push_back("-c"); - args.push_back(path); - args.push_back("-o"); - args.push_back(output); - - system::callExecutable(this->_path, args); - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/compiler/gcc_compiler.hpp b/ct_core/include/ct/external/cppad/cg/model/compiler/gcc_compiler.hpp deleted file mode 100644 index 7f19db082..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/compiler/gcc_compiler.hpp +++ /dev/null @@ -1,128 +0,0 @@ -#ifndef CPPAD_CG_GCC_COMPILER_INCLUDED -#define CPPAD_CG_GCC_COMPILER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * C compiler class used to create a dynamic library - * - * @author Joao Leal - */ -template -class GccCompiler : public AbstractCCompiler { -public: - - GccCompiler(const std::string& gccPath = "/usr/bin/gcc") : - AbstractCCompiler(gccPath) { - - this->_compileFlags.push_back("-O2"); // Optimization level - this->_compileLibFlags.push_back("-O2"); // Optimization level - this->_compileLibFlags.push_back("-shared"); // Make shared object - this->_compileLibFlags.push_back("-rdynamic"); // add all symbols to the dynamic symbol table - } - - GccCompiler(const GccCompiler& orig) = delete; - GccCompiler& operator=(const GccCompiler& rhs) = delete; - - /** - * Creates a dynamic library from a set of object files - * - * @param library the path to the dynamic library to be created - */ - virtual void buildDynamic(const std::string& library, - JobTimer* timer = nullptr) override { - - std::string linkerFlags = "-Wl,-soname," + system::filenameFromPath(library); - for (size_t i = 0; i < this->_linkFlags.size(); i++) - linkerFlags += "," + this->_linkFlags[i]; - - std::vector args; - args.insert(args.end(), this->_compileLibFlags.begin(), this->_compileLibFlags.end()); - args.push_back(linkerFlags); // Pass suitable options to linker - args.push_back("-o"); // Output file name - args.push_back(library); // Output file name - for (const std::string& it : this->_ofiles) { - args.push_back(it); - } - - if (timer != nullptr) { - timer->startingJob("'" + library + "'", JobTimer::COMPILING_DYNAMIC_LIBRARY); - } else if (this->_verbose) { - std::cout << "building library '" << library << "'" << std::endl; - } - - system::callExecutable(this->_path, args); - - if (timer != nullptr) { - timer->finishedJob(); - } - } - - virtual ~GccCompiler() { - } - -protected: - - /** - * Compiles a single source file into an object file - * - * @param source the content of the source file - * @param output the compiled output file name (the object file path) - */ - virtual void compileSource(const std::string& source, - const std::string& output, - bool posIndepCode) override { - std::vector args; - args.push_back("-x"); - args.push_back("c"); // C source files - args.insert(args.end(), this->_compileFlags.begin(), this->_compileFlags.end()); - args.push_back("-c"); - args.push_back("-"); - if (posIndepCode) { - args.push_back("-fPIC"); // position-independent code for dynamic linking - } - args.push_back("-o"); - args.push_back(output); - - system::callExecutable(this->_path, args, nullptr, &source); - } - - virtual void compileFile(const std::string& path, - const std::string& output, - bool posIndepCode) override { - std::vector args; - args.push_back("-x"); - args.push_back("c"); // C source files - args.insert(args.end(), this->_compileFlags.begin(), this->_compileFlags.end()); - if (posIndepCode) { - args.push_back("-fPIC"); // position-independent code for dynamic linking - } - args.push_back("-c"); - args.push_back(path); - args.push_back("-o"); - args.push_back(output); - - system::callExecutable(this->_path, args); - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/ar_archiver.hpp b/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/ar_archiver.hpp deleted file mode 100644 index 48ff2ba40..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/ar_archiver.hpp +++ /dev/null @@ -1,84 +0,0 @@ -#ifndef CPPAD_CG_LINUX_AR_ARCHIVER_INCLUDED -#define CPPAD_CG_LINUX_AR_ARCHIVER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -class ArArchiver : public Archiver { -protected: - std::string _arPath; // the path to the ar executable - std::vector _flags; - bool _verbose; -public: - - inline ArArchiver() : - _arPath("/usr/bin/ar"), - _verbose(false) { - } - - inline ArArchiver(const std::string& arPath) : - _arPath(arPath), - _verbose(false) { - } - - inline virtual bool isVerbose() const { - return _verbose; - } - - inline virtual void setVerbose(bool verbose) { - _verbose = verbose; - } - - inline const std::vector& getFlags() const { - return _flags; - } - - inline void setFlags(const std::vector& flags) { - _flags = flags; - } - - inline virtual void create(const std::string& library, - const std::set& objectFiles, - JobTimer* timer = nullptr) { - // backup output format so that it can be restored - OStreamConfigRestore coutb(std::cout); - - std::vector args; - args.push_back("rcs"); - args.insert(args.end(), _flags.begin(), _flags.end()); - args.push_back(library); // Output file name - args.insert(args.end(), objectFiles.begin(), objectFiles.end()); - - if (timer != nullptr) { - timer->startingJob("'" + library + "'", JobTimer::ASSEMBLE_STATIC_LIBRARY); - } else if (_verbose) { - std::cout << "building library '" << library << "'" << std::endl; - } - - system::callExecutable(_arPath, args); - - if (timer != nullptr) { - timer->finishedJob(); - } - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/archiver.hpp b/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/archiver.hpp deleted file mode 100644 index e2a5184e5..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/archiver.hpp +++ /dev/null @@ -1,43 +0,0 @@ -#ifndef CPPAD_CG_ARCHIVER_INCLUDED -#define CPPAD_CG_ARCHIVER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include - -namespace CppAD { -namespace cg { - -/** - * A tool used to create static libraries from object files - */ -class Archiver { -public: - virtual bool isVerbose() const = 0; - - virtual void setVerbose(bool verbose) = 0; - - virtual void create(const std::string& library, - const std::set& objectFiles, - JobTimer* timer = nullptr) = 0; - - inline virtual ~Archiver() { - }; -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/dynamic_library_processor.hpp b/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/dynamic_library_processor.hpp deleted file mode 100644 index d841f9bef..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/dynamic_library_processor.hpp +++ /dev/null @@ -1,227 +0,0 @@ -#ifndef CPPAD_CG_DYNAMIC_LIBRARY_PROCESSOR_INCLUDED -#define CPPAD_CG_DYNAMIC_LIBRARY_PROCESSOR_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Useful class for generating source code for the creation of a dynamic - * library. - * - * @author Joao Leal - */ -template -class DynamicModelLibraryProcessor : public ModelLibraryProcessor { -protected: - /** - * the path of the dynamic library to be created - */ - std::string _libraryName; - /** - * a custom extension for the dynamic library (e.g. ".so.1") - */ - const std::string* _customLibExtension; - /** - * System dependent custom options - */ - std::map _options; -public: - - /** - * Creates a new helper class for the generation of dynamic libraries - * using the C language. - * - * @param modelLibraryHelper - * @param libraryName The path of the dynamic library to be created - * (without the extension) - */ - inline DynamicModelLibraryProcessor(ModelLibraryCSourceGen& modelLibraryHelper, - const std::string& libraryName = "cppad_cg_model") : - ModelLibraryProcessor(modelLibraryHelper), - _libraryName(libraryName), - _customLibExtension(nullptr) { - } - - inline const std::string& getLibraryName() const { - return _libraryName; - } - - inline void setLibraryName(const std::string& libraryName) { - CPPADCG_ASSERT_KNOWN(!libraryName.empty(), "Library name cannot be empty"); - - _libraryName = libraryName; - } - - /** - * Provides a custom library extension defined by the user - * - * @return a custom library extension - */ - inline const std::string* getCustomLibraryExtension() const { - return _customLibExtension; - } - - /** - * Defines a custom extension for the library that will be created - * - * @param libraryExtension the custom extension name - */ - inline void setCustomLibraryExtension(const std::string& libraryExtension) { - delete _customLibExtension; - _customLibExtension = new std::string(libraryExtension); - } - - /** - * Resets the library extension to the default - */ - inline void removeCustomLibraryExtension() { - delete _customLibExtension; - _customLibExtension = nullptr; - } - - /** - * System dependent custom options - */ - inline std::map& getOptions() { - return _options; - } - - /** - * System dependent custom options - */ - inline const std::map& getOptions() const { - return _options; - } - - /** - * Compiles all models and generates a dynamic library. - * - * @param compiler The compiler used to compile the sources and create - * the dynamic library - * @param loadLib Whether or not to load the dynamic library - * @return The dynamic library if loadLib is true, nullptr otherwise - */ - DynamicLib* createDynamicLibrary(CCompiler& compiler, - bool loadLib = true) { - // backup output format so that it can be restored - OStreamConfigRestore coutb(std::cout); - - this->modelLibraryHelper_->startingJob("", JobTimer::DYNAMIC_MODEL_LIBRARY); - - const std::map*>& models = this->modelLibraryHelper_->getModels(); - try { - for (const auto& p : models) { - const std::map& modelSources = this->getSources(*p.second); - - this->modelLibraryHelper_->startingJob("", JobTimer::COMPILING_FOR_MODEL); - compiler.compileSources(modelSources, true, this->modelLibraryHelper_); - this->modelLibraryHelper_->finishedJob(); - } - - const std::map& sources = this->getLibrarySources(); - compiler.compileSources(sources, true, this->modelLibraryHelper_); - - const std::map& customSource = this->modelLibraryHelper_->getCustomSources(); - compiler.compileSources(customSource, true, this->modelLibraryHelper_); - - std::string libname = _libraryName; - if (_customLibExtension != nullptr) - libname += *_customLibExtension; - else - libname += system::SystemInfo<>::DYNAMIC_LIB_EXTENSION; - - compiler.buildDynamic(libname, this->modelLibraryHelper_); - - } catch (...) { - compiler.cleanup(); - throw; - } - compiler.cleanup(); - - this->modelLibraryHelper_->finishedJob(); - - if (loadLib) - return loadDynamicLibrary(); - else - return nullptr; - } - - /** - * Compiles all models and generates a static library. - * - * @param compiler The compiler used to compile the sources - * @param ar The archiver used to assemble the compiled source into a - * static library - * @param posIndepCode Whether or not to compile the source - * with position independent code (static libraries - * typically do not use this feature) - */ - - void createStaticLibrary(CCompiler& compiler, - Archiver& ar, - bool posIndepCode) { - // backup output format so that it can be restored - OStreamConfigRestore coutb(std::cout); - - this->modelLibraryHelper_->startingJob("", JobTimer::STATIC_MODEL_LIBRARY); - - const std::map*>& models = this->modelLibraryHelper_->getModels(); - try { - for (const auto& p : models) { - const std::map& modelSources = this->getSources(*p.second); - - this->modelLibraryHelper_->startingJob("", JobTimer::COMPILING_FOR_MODEL); - compiler.compileSources(modelSources, posIndepCode, this->modelLibraryHelper_); - this->modelLibraryHelper_->finishedJob(); - } - - const std::map& sources = this->getLibrarySources(); - compiler.compileSources(sources, posIndepCode, this->modelLibraryHelper_); - - const std::map& customSource = this->modelLibraryHelper_->getCustomSources(); - compiler.compileSources(customSource, posIndepCode, this->modelLibraryHelper_); - - std::string libname = _libraryName; - if (_customLibExtension != nullptr) - libname += *_customLibExtension; - else - libname += system::SystemInfo<>::STATIC_LIB_EXTENSION; - - ar.create(libname, compiler.getObjectFiles(), this->modelLibraryHelper_); - } catch (...) { - compiler.cleanup(); - throw; - } - compiler.cleanup(); - - this->modelLibraryHelper_->finishedJob(); - } - - virtual ~DynamicModelLibraryProcessor() { - delete _customLibExtension; - } - -protected: - - virtual DynamicLib* loadDynamicLibrary(); - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/dynamiclib.hpp b/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/dynamiclib.hpp deleted file mode 100644 index e63a204a3..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/dynamiclib.hpp +++ /dev/null @@ -1,38 +0,0 @@ -#ifndef CPPAD_CG_DYNAMICLIB_INCLUDED -#define CPPAD_CG_DYNAMICLIB_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Abstract class used to load compiled models in a dynamic library - * - * @author Joao Leal - */ -template -class DynamicLib : public FunctorModelLibrary { -public: - - inline virtual ~DynamicLib() { - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/linux/linux_dynamic_model_library_processor.hpp b/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/linux/linux_dynamic_model_library_processor.hpp deleted file mode 100644 index aed808f04..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/linux/linux_dynamic_model_library_processor.hpp +++ /dev/null @@ -1,37 +0,0 @@ -#ifndef CPPAD_CG_LINUX_C_LANG_COMPILE_DYNAMIC_HELPER_INCLUDED -#define CPPAD_CG_LINUX_C_LANG_COMPILE_DYNAMIC_HELPER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ -#if CPPAD_CG_SYSTEM_LINUX - -namespace CppAD { -namespace cg { - -template -DynamicLib* DynamicModelLibraryProcessor::loadDynamicLibrary() { - const auto it = _options.find("dlOpenMode"); - if (it == _options.end()) { - return new LinuxDynamicLib(_libraryName + system::SystemInfo<>::DYNAMIC_LIB_EXTENSION); - } else { - int dlOpenMode = std::stoi(it->second); - return new LinuxDynamicLib(_libraryName + system::SystemInfo<>::DYNAMIC_LIB_EXTENSION, dlOpenMode); - } -} - -} // END cg namespace -} // END CppAD namespace - -#endif -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/linux/linux_dynamiclib.hpp b/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/linux/linux_dynamiclib.hpp deleted file mode 100644 index 1058ceee8..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/linux/linux_dynamiclib.hpp +++ /dev/null @@ -1,117 +0,0 @@ -#ifndef CPPAD_CG_LINUX_DYNAMICLIB_INCLUDED -#define CPPAD_CG_LINUX_DYNAMICLIB_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ -#if CPPAD_CG_SYSTEM_LINUX - -#include -#include - -namespace CppAD { -namespace cg { - -/** - * Useful class to call the compiled source code in a dynamic library. - * For the Linux Operating System only. - * - * @author Joao Leal - */ -template -class LinuxDynamicLib : public DynamicLib { -protected: - const std::string _dynLibName; - /// the dynamic library handler - void* _dynLibHandle; - std::set*> _models; -public: - - LinuxDynamicLib(const std::string& dynLibName, - int dlOpenMode = RTLD_NOW) : - _dynLibName(dynLibName), - _dynLibHandle(nullptr) { - - std::string path; - if (dynLibName[0] == '/') { - path = dynLibName; // absolute path - } else if (!(dynLibName[0] == '.' && dynLibName[1] == '/') && - !(dynLibName[0] == '.' && dynLibName[1] == '.')) { - path = "./" + dynLibName; // relative path - } else { - path = dynLibName; - } - - // load the dynamic library - _dynLibHandle = dlopen(path.c_str(), dlOpenMode); - CPPADCG_ASSERT_KNOWN(_dynLibHandle != nullptr, ("Failed to dynamically load library '" + dynLibName + "': " + dlerror()).c_str()); - - // validate the dynamic library - this->validate(); - } - - LinuxDynamicLib(const LinuxDynamicLib&) = delete; - LinuxDynamicLib& operator=(const LinuxDynamicLib&) = delete; - - virtual LinuxDynamicLibModel* model(const std::string& modelName) override { - std::set::const_iterator it = this->_modelNames.find(modelName); - if (it == this->_modelNames.end()) { - return nullptr; - } - LinuxDynamicLibModel* m = new LinuxDynamicLibModel (this, modelName); - _models.insert(m); - return m; - } - - virtual void* loadFunction(const std::string& functionName, bool required = true) override { - void* functor = dlsym(_dynLibHandle, functionName.c_str()); - - if (required) { - char *err = dlerror(); - if (err != nullptr) - throw CGException("Failed to load function '", functionName, "': ", err); - } - - return functor; - } - - virtual ~LinuxDynamicLib() { - for (LinuxDynamicLibModel* model : _models) { - model->modelLibraryClosed(); - } - - if (_dynLibHandle != nullptr) { - if(this->_onClose != nullptr) { - (*this->_onClose)(); - } - - dlclose(_dynLibHandle); - _dynLibHandle = nullptr; - } - } - -protected: - - virtual void destroyed(LinuxDynamicLibModel* model) { - _models.erase(model); - } - - friend class LinuxDynamicLibModel; - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/linux/linux_dynamiclib_model.hpp b/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/linux/linux_dynamiclib_model.hpp deleted file mode 100644 index c6579b63c..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/dynamic_lib/linux/linux_dynamiclib_model.hpp +++ /dev/null @@ -1,80 +0,0 @@ -#ifndef CPPAD_CG_LINUX_DYNAMICLIB_MODEL_INCLUDED -#define CPPAD_CG_LINUX_DYNAMICLIB_MODEL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ -#if CPPAD_CG_SYSTEM_LINUX - -#include -#include - -namespace CppAD { -namespace cg { - -/** - * Useful class to call the compiled model in a dynamic library. - * For the Linux Operating System only. - * - * @author Joao Leal - */ -template -class LinuxDynamicLibModel : public FunctorGenericModel { -protected: - /// the dynamic library - LinuxDynamicLib* _dynLib; - -public: - - virtual ~LinuxDynamicLibModel() { - if (_dynLib != nullptr) { - _dynLib->destroyed(this); - } - } - -protected: - - /** - * Creates a new model - * - * @param name The model name - */ - LinuxDynamicLibModel(LinuxDynamicLib* dynLib, const std::string& name) : - FunctorGenericModel(name), - _dynLib(dynLib) { - - CPPADCG_ASSERT_UNKNOWN(_dynLib != nullptr); - - this->init(); - } - - LinuxDynamicLibModel(const LinuxDynamicLibModel&) = delete; - LinuxDynamicLibModel& operator=(const LinuxDynamicLibModel&) = delete; - - virtual void* loadFunction(const std::string& functionName, bool required = true) override { - return _dynLib->loadFunction(functionName, required); - } - - virtual void modelLibraryClosed() override { - _dynLib = nullptr; - FunctorGenericModel::modelLibraryClosed(); - } - - friend class LinuxDynamicLib; -}; - -} // END cg namespace -} // END CppAD namespace - -#endif -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/external_function_wrapper.hpp b/ct_core/include/ct/external/cppad/cg/model/external_function_wrapper.hpp deleted file mode 100644 index aa9eca8b6..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/external_function_wrapper.hpp +++ /dev/null @@ -1,65 +0,0 @@ -#ifndef CPPAD_CG_EXTERNAL_FUNCTION_WRAPPER_INCLUDED -#define CPPAD_CG_EXTERNAL_FUNCTION_WRAPPER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -class ExternalFunctionWrapper { -public: - /** - * Computes results during a forward mode sweep, the Taylor coefficients - * for dependent variables relative to independent variables. - * - * @param libModel The model calling where this is being called from. - * @param q Lowest order for this forward mode calculation. - * @param p Highest order for this forward mode calculation. - * @param tx Independent variable Taylor coefficients. - * @param ty Dependent variable Taylor coefficients. - * @return true if evaluation succeeded, false otherwise. - */ - virtual bool forward(FunctorGenericModel& libModel, - int q, - int p, - const Array tx[], - Array& ty) = 0; - - /** - * Computes results during a reverse mode sweep, the adjoints or partial - * derivatives of independent variables. - * - * @param libModel The model calling where this is being called from. - * @param p Order for this reverse mode calculation. - * @param tx Independent variable Taylor coefficients. - * @param px Independent variable partial derivatives. - * @param py Dependent variable partial derivatives. - * @return true if evaluation succeeded, false otherwise. - */ - virtual bool reverse(FunctorGenericModel& libModel, - int p, - const Array tx[], - Array& px, - const Array py[]) = 0; - - inline virtual ~ExternalFunctionWrapper() { - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/functor_generic_model.hpp b/ct_core/include/ct/external/cppad/cg/model/functor_generic_model.hpp deleted file mode 100644 index 921b491e0..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/functor_generic_model.hpp +++ /dev/null @@ -1,1077 +0,0 @@ -#ifndef CPPAD_CG_FUNCTOR_GENERIC_MODEL_INCLUDED -#define CPPAD_CG_FUNCTOR_GENERIC_MODEL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include - -namespace CppAD { -namespace cg { - -/** - * A model which can be accessed through function pointers. - * This class is not thread-safe and it should not be used simultaneously in - * different threads. - * Multiple instances of this class for the same model from the same model - * library object can be used simulataneously in different threads. - * - * @author Joao Leal - */ -template -class FunctorGenericModel : public GenericModel { -protected: - bool _isLibraryReady; - /// the model name - const std::string _name; - size_t _m; - size_t _n; - std::vector _in; - std::vector _inHess; - std::vector _out; - LangCAtomicFun _atomicFuncArg; - std::vector* > _atomic; - size_t _missingAtomicFunctions; - CppAD::vector _tx, _ty, _px, _py; - // original model function - void (*_zero)(Base const*const*, Base * const*, LangCAtomicFun); - // first order forward mode - int (*_forwardOne)(Base const tx[], Base ty[], LangCAtomicFun); - // first order reverse mode - int (*_reverseOne)(Base const tx[], Base const ty[], Base px[], Base const py[], LangCAtomicFun); - // second order reverse mode - int (*_reverseTwo)(Base const tx[], Base const ty[], Base px[], Base const py[], LangCAtomicFun); - // jacobian function in the dynamic library - void (*_jacobian)(Base const*const*, Base * const*, LangCAtomicFun); - // hessian function in the dynamic library - void (*_hessian)(Base const*const*, Base * const*, LangCAtomicFun); - // - int (*_sparseForwardOne)(unsigned long, Base const *const *, Base * const *, LangCAtomicFun); - // - int (*_sparseReverseOne)(unsigned long, Base const *const *, Base * const *, LangCAtomicFun); - // - int (*_sparseReverseTwo)(unsigned long, Base const *const *, Base * const *, LangCAtomicFun); - // sparse jacobian function in the dynamic library - void (*_sparseJacobian)(Base const*const*, Base * const*, LangCAtomicFun); - // sparse hessian function in the dynamic library - void (*_sparseHessian)(Base const*const*, Base * const*, LangCAtomicFun); - // - void (*_forwardOneSparsity)(unsigned long, unsigned long const**, unsigned long*); - // - void (*_reverseOneSparsity)(unsigned long, unsigned long const**, unsigned long*); - // - void (*_reverseTwoSparsity)(unsigned long, unsigned long const**, unsigned long*); - // jacobian sparsity function in the dynamic library - void (*_jacobianSparsity)(unsigned long const** row, - unsigned long const** col, - unsigned long * nnz); - // hessian sparsity function in the dynamic library - void (*_hessianSparsity)(unsigned long const** row, - unsigned long const** col, - unsigned long * nnz); - void (*_hessianSparsity2)(unsigned long i, - unsigned long const** row, - unsigned long const** col, - unsigned long * nnz); - void (*_atomicFunctions)(const char*** names, - unsigned long * n); - -public: - - FunctorGenericModel(const FunctorGenericModel&) = delete; - FunctorGenericModel& operator=(const FunctorGenericModel&) = delete; - - virtual const std::string& getName() const override { - return _name; - } - - virtual bool addAtomicFunction(atomic_base& atomic) override { - return addExternalFunction, AtomicExternalFunctionWrapper > - (atomic, atomic.afun_name()); - } - - virtual bool addExternalModel(GenericModel& atomic) override { - return addExternalFunction, GenericModelExternalFunctionWrapper > - (atomic, atomic.getName()); - } - - // Jacobian sparsity - virtual bool isJacobianSparsityAvailable() override { - return _jacobianSparsity != nullptr; - } - - virtual std::vector JacobianSparsityBool() override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Dynamic library closed"); - CPPADCG_ASSERT_KNOWN(_jacobianSparsity != nullptr, "No Jacobian sparsity function defined in the dynamic library"); - - unsigned long const* row, *col; - unsigned long nnz; - (*_jacobianSparsity)(&row, &col, &nnz); - - bool set_type = true; - std::vector s; - - loadSparsity(set_type, s, _m, _n, row, col, nnz); - - return s; - } - - virtual std::vector > JacobianSparsitySet() override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_jacobianSparsity != nullptr, "No Jacobian sparsity function defined in the dynamic library"); - - unsigned long const* row, *col; - unsigned long nnz; - (*_jacobianSparsity)(&row, &col, &nnz); - - std::set set_type; - std::vector > s; - - loadSparsity(set_type, s, _m, _n, row, col, nnz); - - return s; - } - - virtual void JacobianSparsity(std::vector& rows, - std::vector& cols) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_jacobianSparsity != nullptr, "No Jacobian sparsity function defined in the dynamic library"); - - unsigned long const* row, *col; - unsigned long nnz; - (*_jacobianSparsity)(&row, &col, &nnz); - - rows.resize(nnz); - cols.resize(nnz); - - std::copy(row, row + nnz, rows.begin()); - std::copy(col, col + nnz, cols.begin()); - } - - // Hessian sparsity - virtual bool isHessianSparsityAvailable() override { - return _hessianSparsity != nullptr; - } - - virtual std::vector HessianSparsityBool() override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_hessianSparsity != nullptr, "No Hessian sparsity function defined in the dynamic library"); - - unsigned long const* row, *col; - unsigned long nnz; - (*_hessianSparsity)(&row, &col, &nnz); - - bool set_type = true; - std::vector s; - - loadSparsity(set_type, s, _n, _n, row, col, nnz); - - return s; - } - - virtual std::vector > HessianSparsitySet() override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_hessianSparsity != nullptr, "No Hessian sparsity function defined in the dynamic library"); - - unsigned long const* row, *col; - unsigned long nnz; - (*_hessianSparsity)(&row, &col, &nnz); - - std::set set_type; - std::vector > s; - - loadSparsity(set_type, s, _n, _n, row, col, nnz); - - return s; - } - - virtual void HessianSparsity(std::vector& rows, - std::vector& cols) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_hessianSparsity != nullptr, "No Hessian sparsity function defined in the dynamic library"); - - unsigned long const* row, *col; - unsigned long nnz; - (*_hessianSparsity)(&row, &col, &nnz); - - rows.resize(nnz); - cols.resize(nnz); - - std::copy(row, row + nnz, rows.begin()); - std::copy(col, col + nnz, cols.begin()); - } - - virtual bool isEquationHessianSparsityAvailable() override { - return _hessianSparsity2 != nullptr; - } - - virtual std::vector HessianSparsityBool(size_t i) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_hessianSparsity2 != nullptr, "No Hessian sparsity function defined in the dynamic library"); - - unsigned long const* row, *col; - unsigned long nnz; - (*_hessianSparsity2)(i, &row, &col, &nnz); - - bool set_type = true; - std::vector s; - - loadSparsity(set_type, s, _n, _n, row, col, nnz); - - return s; - } - - virtual std::vector > HessianSparsitySet(size_t i) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_hessianSparsity2 != nullptr, "No Hessian sparsity function defined in the dynamic library"); - - unsigned long const* row, *col; - unsigned long nnz; - (*_hessianSparsity2)(i, &row, &col, &nnz); - - std::set set_type; - std::vector > s; - - loadSparsity(set_type, s, _n, _n, row, col, nnz); - - return s; - } - - virtual void HessianSparsity(size_t i, std::vector& rows, - std::vector& cols) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_hessianSparsity2 != nullptr, "No Hessian sparsity function defined in the dynamic library"); - - unsigned long const* row, *col; - unsigned long nnz; - (*_hessianSparsity2)(i, &row, &col, &nnz); - - rows.resize(nnz); - cols.resize(nnz); - - std::copy(row, row + nnz, rows.begin()); - std::copy(col, col + nnz, cols.begin()); - } - - /// number of independent variables - - virtual size_t Domain() const override { - return _n; - } - - /// number of dependent variables - - virtual size_t Range() const override { - return _m; - } - - virtual bool isForwardZeroAvailable() override { - return _zero != nullptr; - } - - /// calculate the dependent values (zero order) - virtual void ForwardZero(const Base* x, size_t x_size, Base* dep, size_t dep_size) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_zero != nullptr, "No zero order forward function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(_in.size() == 1, "The number of independent variable arrays is higher than 1," - " please use the variable size methods"); - CPPADCG_ASSERT_KNOWN(dep_size == _m, "Invalid dependent array size"); - CPPADCG_ASSERT_KNOWN(x_size == _n, "Invalid independent array size"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - - _in[0] = x; - _out[0] = dep; - - (*_zero)(&_in[0], &_out[0], _atomicFuncArg); - } - - virtual void ForwardZero(const std::vector &x, - Base* dep, size_t dep_size) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_zero != nullptr, "No zero order forward function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(_in.size() == x.size(), "The number of independent variable arrays is invalid"); - CPPADCG_ASSERT_KNOWN(dep_size == _m, "Invalid dependent array size"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - _out[0] = dep; - - (*_zero)(&x[0], &_out[0], _atomicFuncArg); - } - - virtual void ForwardZero(const CppAD::vector& vx, - CppAD::vector& vy, - const CppAD::vector &tx, - CppAD::vector& ty) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_zero != nullptr, "No zero order forward function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(_in.size() == 1, "The number of independent variable arrays is higher than 1," - " please use the variable size methods"); - CPPADCG_ASSERT_KNOWN(tx.size() == _n, "Invalid independent array size"); - CPPADCG_ASSERT_KNOWN(ty.size() == _m, "Invalid dependent array size"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - _in[0] = &tx[0]; - _out[0] = &ty[0]; - - (*_zero)(&_in[0], &_out[0], _atomicFuncArg); - - if (vx.size() > 0) { - CPPADCG_ASSERT_KNOWN(vx.size() >= _n, "Invalid vx size"); - CPPADCG_ASSERT_KNOWN(vy.size() >= _m, "Invalid vy size"); - const std::vector > jacSparsity = JacobianSparsitySet(); - for (size_t i = 0; i < _m; i++) { - for (size_t j : jacSparsity[i]) { - if (vx[j]) { - vy[i] = true; - break; - } - } - } - } - } - - virtual bool isJacobianAvailable() override { - return _jacobian != nullptr; - } - - /// calculate entire Jacobian - virtual void Jacobian(const Base* x, size_t x_size, - Base* jac, size_t jac_size) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_jacobian != nullptr, "No Jacobian function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(_in.size() == 1, "The number of independent variable arrays is higher than 1," - " please use the variable size methods"); - CPPADCG_ASSERT_KNOWN(x_size == _n, "Invalid independent array size"); - CPPADCG_ASSERT_KNOWN(jac_size == _m * _n, "Invalid Jacobian array size"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - - _in[0] = x; - _out[0] = jac; - - (*_jacobian)(&_in[0], &_out[0], _atomicFuncArg); - } - - virtual bool isHessianAvailable() override { - return _hessian != nullptr; - } - - /// calculate Hessian for one component of f - virtual void Hessian(const Base* x, size_t x_size, - const Base* w, size_t w_size, - Base* hess) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_hessian != nullptr, "No Hessian function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(_in.size() == 1, "The number of independent variable arrays is higher than 1," - " please use the variable size methods"); - CPPADCG_ASSERT_KNOWN(x_size == _n, "Invalid independent array size"); - CPPADCG_ASSERT_KNOWN(w_size == _m, "Invalid multiplier array size"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - _inHess[0] = x; - _inHess[1] = w; - _out[0] = hess; - - (*_hessian)(&_inHess[0], &_out[0], _atomicFuncArg); - } - - virtual bool isForwardOneAvailable() override { - return _forwardOne != nullptr; - } - - virtual void ForwardOne(const Base tx[], size_t tx_size, - Base ty[], size_t ty_size) override { - const size_t k = 1; - - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_forwardOne != nullptr, "No forward one function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(tx_size >= (k + 1) * _n, "Invalid tx size"); - CPPADCG_ASSERT_KNOWN(ty_size >= (k + 1) * _m, "Invalid ty size"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - int ret = (*_forwardOne)(tx, ty, _atomicFuncArg); - - CPPADCG_ASSERT_KNOWN(ret == 0, "First-order forward mode failed."); // generic failure - } - - virtual bool isSparseForwardOneAvailable() override { - return _forwardOneSparsity != nullptr && _sparseForwardOne != nullptr; - } - - virtual void ForwardOne(const Base x[], size_t x_size, - size_t tx1Nnz, const size_t idx[], const Base tx1[], - Base ty1[], size_t ty1_size) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_sparseForwardOne != nullptr, "No sparse forward one function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(_forwardOneSparsity != nullptr, "No forward one sparsity function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(x_size >= _n, "Invalid x size"); - CPPADCG_ASSERT_KNOWN(ty1_size >= _m, "Invalid ty1 size"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - std::fill(ty1, ty1 + _m, Base(0)); - if (tx1Nnz == 0) - return; //nothing to do - - unsigned long const* pos; - size_t nnz = 0; - - if (_ty.size() < _m) - _ty.resize(_m); - Base* compressed = &_ty[0]; - - _inHess[0] = x; - _out[0] = compressed; - - for (size_t ej = 0; ej < tx1Nnz; ej++) { - size_t j = idx[ej]; - (*_forwardOneSparsity)(j, &pos, &nnz); - - _inHess[1] = &tx1[ej]; - (*_sparseForwardOne)(j, &_inHess[0], &_out[0], _atomicFuncArg); - - for (size_t ePos = 0; ePos < nnz; ePos++) { - ty1[pos[ePos]] += compressed[ePos]; - } - } - } - - virtual bool isReverseOneAvailable() override { - return _reverseOne != nullptr; - } - - virtual void ReverseOne(const Base tx[], size_t tx_size, - const Base ty[], size_t ty_size, - Base px[], size_t px_size, - const Base py[], size_t py_size) override { - const size_t k = 0; - const size_t k1 = k + 1; - - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_reverseOne != nullptr, "No reverse one function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(tx_size >= k1 * _n, "Invalid tx size"); - CPPADCG_ASSERT_KNOWN(ty_size >= k1 * _m, "Invalid ty size"); - CPPADCG_ASSERT_KNOWN(px_size >= k1 * _n, "Invalid px size"); - CPPADCG_ASSERT_KNOWN(py_size >= k1 * _m, "Invalid py size"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - int ret = (*_reverseOne)(tx, ty, px, py, _atomicFuncArg); - - CPPADCG_ASSERT_KNOWN(ret == 0, "First-order reverse mode failed."); - } - - virtual bool isSparseReverseOneAvailable() override { - return _reverseOneSparsity != nullptr && _sparseReverseOne != nullptr; - } - - virtual void ReverseOne(const Base x[], size_t x_size, - Base px[], size_t px_size, - size_t pyNnz, const size_t idx[], const Base py[]) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_sparseReverseOne != nullptr, "No sparse reverse one function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(_reverseOneSparsity != nullptr, "No reverse one sparsity function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(x_size >= _n, "Invalid x size"); - CPPADCG_ASSERT_KNOWN(px_size >= _n, "Invalid px size"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - std::fill(px, px + _n, Base(0)); - if (pyNnz == 0) - return; //nothing to do - - unsigned long const* pos; - size_t nnz = 0; - - if (_px.size() < _n) - _px.resize(_n); - Base* compressed = &_px[0]; - - _inHess[0] = x; - _out[0] = compressed; - - for (size_t ei = 0; ei < pyNnz; ei++) { - size_t i = idx[ei]; - (*_reverseOneSparsity)(i, &pos, &nnz); - - _inHess[1] = &py[ei]; - (*_sparseReverseOne)(i, &_inHess[0], &_out[0], _atomicFuncArg); - - for (size_t ePos = 0; ePos < nnz; ePos++) { - px[pos[ePos]] += compressed[ePos]; - } - } - } - - virtual bool isReverseTwoAvailable() override { - return _reverseTwo != nullptr; - } - - virtual void ReverseTwo(const Base tx[], size_t tx_size, - const Base ty[], size_t ty_size, - Base px[], size_t px_size, - const Base py[], size_t py_size) override { - const size_t k = 1; - const size_t k1 = k + 1; - - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_reverseTwo != nullptr, "No sparse reverse two function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(_in.size() == 1, "The number of independent variable arrays is higher than 1"); - CPPADCG_ASSERT_KNOWN(tx_size >= k1 * _n, "Invalid tx size"); - CPPADCG_ASSERT_KNOWN(ty_size >= k1 * _m, "Invalid ty size"); - CPPADCG_ASSERT_KNOWN(px_size >= k1 * _n, "Invalid px size"); - CPPADCG_ASSERT_KNOWN(py_size >= k1 * _m, "Invalid py size"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - int ret = (*_reverseTwo)(tx, ty, px, py, _atomicFuncArg); - - CPPADCG_ASSERT_KNOWN(ret != 1, "Second-order reverse mode failed: py[2*i] (i=0...m) must be zero."); - CPPADCG_ASSERT_KNOWN(ret == 0, "Second-order reverse mode failed."); - } - - virtual bool isSparseReverseTwoAvailable() override { - return _sparseReverseTwo != nullptr; - } - - virtual void ReverseTwo(const Base x[], size_t x_size, - size_t tx1Nnz, const size_t idx[], const Base tx1[], - Base px2[], size_t px2_size, - const Base py2[], size_t py2_size) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_sparseReverseTwo != nullptr, "No sparse reverse two function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(_reverseTwoSparsity != nullptr, "No reverse two sparsity function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(x_size >= _n, "Invalid x size"); - CPPADCG_ASSERT_KNOWN(px2_size >= _n, "Invalid px2 size"); - CPPADCG_ASSERT_KNOWN(py2_size >= _m, "Invalid py2 size"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - std::fill(px2, px2 + _n, Base(0)); - if (tx1Nnz == 0) - return; //nothing to do - - unsigned long const* pos; - size_t nnz = 0; - - if (_px.size() < _n) - _px.resize(_n); - Base* compressed = &_px[0]; - - const Base * in[3]; - in[0] = x; - in[2] = py2; - _out[0] = compressed; - - for (size_t ej = 0; ej < tx1Nnz; ej++) { - size_t j = idx[ej]; - (*_reverseTwoSparsity)(j, &pos, &nnz); - - in[1] = &tx1[ej]; - (*_sparseReverseTwo)(j, &in[0], &_out[0], _atomicFuncArg); - - for (size_t ePos = 0; ePos < nnz; ePos++) { - px2[pos[ePos]] += compressed[ePos]; - } - } - } - - virtual bool isSparseJacobianAvailable() override { - return _jacobianSparsity != nullptr && _sparseJacobian != nullptr; - } - - /// calculate sparse Jacobians - - virtual void SparseJacobian(const Base* x, size_t x_size, - Base* jac, size_t jac_size) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_sparseJacobian != nullptr, "No sparse jacobian function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(_in.size() == 1, "The number of independent variable arrays is higher than 1," - " please use the variable size methods"); - CPPADCG_ASSERT_KNOWN(x_size == _n, "Invalid independent array size"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - unsigned long const* row; - unsigned long const* col; - unsigned long nnz; - (*_jacobianSparsity)(&row, &col, &nnz); - - CppAD::vector compressed(nnz); - - if (nnz > 0) { - _in[0] = x; - _out[0] = &compressed[0]; - - (*_sparseJacobian)(&_in[0], &_out[0], _atomicFuncArg); - } - - createDenseFromSparse(compressed, - _m, _n, - row, col, - nnz, - jac, jac_size); - } - - virtual void SparseJacobian(const std::vector &x, - std::vector& jac, - std::vector& row, - std::vector& col) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_sparseJacobian != nullptr, "No sparse Jacobian function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(_in.size() == 1, "The number of independent variable arrays is higher than 1," - " please use the variable size methods"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - unsigned long const* drow; - unsigned long const* dcol; - unsigned long nnz; - (*_jacobianSparsity)(&drow, &dcol, &nnz); - - jac.resize(nnz); - row.resize(nnz); - col.resize(nnz); - - if (nnz > 0) { - _in[0] = &x[0]; - _out[0] = &jac[0]; - - (*_sparseJacobian)(&_in[0], &_out[0], _atomicFuncArg); - std::copy(drow, drow + nnz, row.begin()); - std::copy(dcol, dcol + nnz, col.begin()); - } - } - - virtual void SparseJacobian(const Base* x, size_t x_size, - Base* jac, - size_t const** row, - size_t const** col, - size_t nnz) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_sparseJacobian != nullptr, "No sparse Jacobian function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(_in.size() == 1, "The number of independent variable arrays is higher than 1," - " please use the variable size methods"); - CPPADCG_ASSERT_KNOWN(x_size == _n, "Invalid independent array size"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - unsigned long const* drow; - unsigned long const* dcol; - unsigned long K; - (*_jacobianSparsity)(&drow, &dcol, &K); - CPPADCG_ASSERT_KNOWN(K == nnz, "Invalid number of non-zero elements in Jacobian"); - *row = drow; - *col = dcol; - - if (nnz > 0) { - _in[0] = x; - _out[0] = jac; - - (*_sparseJacobian)(&_in[0], &_out[0], _atomicFuncArg); - } - } - - virtual void SparseJacobian(const std::vector& x, - Base* jac, - size_t const** row, - size_t const** col, - size_t nnz) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_sparseJacobian != nullptr, "No sparse Jacobian function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(_in.size() == x.size(), "The number of independent variable arrays is invalid"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - unsigned long const* drow; - unsigned long const* dcol; - unsigned long K; - (*_jacobianSparsity)(&drow, &dcol, &K); - CPPADCG_ASSERT_KNOWN(K == nnz, "Invalid number of non-zero elements in Jacobian"); - *row = drow; - *col = dcol; - - if (nnz > 0) { - _out[0] = jac; - - (*_sparseJacobian)(&x[0], &_out[0], _atomicFuncArg); - } - } - - virtual bool isSparseHessianAvailable() override { - return _hessianSparsity != nullptr && _sparseHessian != nullptr; - } - - /// calculate sparse Hessians - - virtual void SparseHessian(const Base* x, size_t x_size, - const Base* w, size_t w_size, - Base* hess, size_t hess_size) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_sparseHessian != nullptr, "No sparse Hessian function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(x_size == _n, "Invalid independent array size"); - CPPADCG_ASSERT_KNOWN(w_size == _m, "Invalid multiplier array size"); - CPPADCG_ASSERT_KNOWN(_in.size() == 1, "The number of independent variable arrays is higher than 1," - " please use the variable size methods"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - unsigned long const* row, *col; - unsigned long nnz; - (*_hessianSparsity)(&row, &col, &nnz); - - CppAD::vector compressed(nnz); - if (nnz > 0) { - _inHess[0] = x; - _inHess[1] = w; - _out[0] = &compressed[0]; - - (*_sparseHessian)(&_inHess[0], &_out[0], _atomicFuncArg); - } - - createDenseFromSparse(compressed, - _n, _n, - row, col, - nnz, - hess, hess_size); - } - - virtual void SparseHessian(const std::vector &x, - const std::vector &w, - std::vector& hess, - std::vector& row, - std::vector& col) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_sparseHessian != nullptr, "No sparse Hessian function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(x.size() == _n, "Invalid independent array size"); - CPPADCG_ASSERT_KNOWN(w.size() == _m, "Invalid multiplier array size"); - CPPADCG_ASSERT_KNOWN(_in.size() == 1, "The number of independent variable arrays is higher than 1," - " please use the variable size methods"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - unsigned long const* drow, *dcol; - unsigned long nnz; - (*_hessianSparsity)(&drow, &dcol, &nnz); - - hess.resize(nnz); - row.resize(nnz); - col.resize(nnz); - - if (nnz > 0) { - std::copy(drow, drow + nnz, row.begin()); - std::copy(dcol, dcol + nnz, col.begin()); - - _inHess[0] = &x[0]; - _inHess[1] = &w[0]; - _out[0] = &hess[0]; - - (*_sparseHessian)(&_inHess[0], &_out[0], _atomicFuncArg); - } - } - - virtual void SparseHessian(const Base* x, size_t x_size, - const Base* w, size_t w_size, - Base* hess, - size_t const** row, - size_t const** col, - size_t nnz) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_sparseHessian != nullptr, "No sparse Hessian function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(_in.size() == 1, "The number of independent variable arrays is higher than 1," - " please use the variable size methods"); - CPPADCG_ASSERT_KNOWN(x_size == _n, "Invalid independent array size"); - CPPADCG_ASSERT_KNOWN(w_size == _m, "Invalid multiplier array size"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - unsigned long const* drow, *dcol; - unsigned long K; - (*_hessianSparsity)(&drow, &dcol, &K); - CPPADCG_ASSERT_KNOWN(K == nnz, "Invalid number of non-zero elements in Hessian"); - *row = drow; - *col = dcol; - - if (nnz > 0) { - _inHess[0] = x; - _inHess[1] = w; - _out[0] = hess; - - (*_sparseHessian)(&_inHess[0], &_out[0], _atomicFuncArg); - } - } - - virtual void SparseHessian(const std::vector& x, - const Base* w, size_t w_size, - Base* hess, - size_t const** row, - size_t const** col, - size_t nnz) override { - CPPADCG_ASSERT_KNOWN(_isLibraryReady, "Model library is not ready (possibly closed)"); - CPPADCG_ASSERT_KNOWN(_sparseHessian != nullptr, "No sparse Hessian function defined in the dynamic library"); - CPPADCG_ASSERT_KNOWN(_in.size() == x.size(), "The number of independent variable arrays is invalid"); - CPPADCG_ASSERT_KNOWN(w_size == _m, "Invalid multiplier array size"); - CPPADCG_ASSERT_KNOWN(_missingAtomicFunctions == 0, "Some atomic functions used by the compiled model have not been specified yet"); - - unsigned long const* drow, *dcol; - unsigned long K; - (*_hessianSparsity)(&drow, &dcol, &K); - CPPADCG_ASSERT_KNOWN(K == nnz, "Invalid number of non-zero elements in Hessian"); - *row = drow; - *col = dcol; - - if (nnz > 0) { - std::copy(x.begin(), x.end(), _inHess.begin()); - _inHess.back() = w; // the index might not be 1 - _out[0] = hess; - - (*_sparseHessian)(&_inHess[0], &_out[0], _atomicFuncArg); - } - } - - virtual ~FunctorGenericModel() { - for (size_t i = 0; i < _atomic.size(); i++) { - delete _atomic[i]; - } - } - -protected: - - /** - * Creates a new model - * - * @param name The model name - */ - FunctorGenericModel(const std::string& name) : - _isLibraryReady(false), - _name(name), - _m(0), - _n(0), - _atomicFuncArg{nullptr}, // not really required - _missingAtomicFunctions(0), - _zero(nullptr), - _forwardOne(nullptr), - _reverseOne(nullptr), - _reverseTwo(nullptr), - _jacobian(nullptr), - _hessian(nullptr), - _sparseForwardOne(nullptr), - _sparseReverseOne(nullptr), - _sparseReverseTwo(nullptr), - _sparseJacobian(nullptr), - _sparseHessian(nullptr), - _forwardOneSparsity(nullptr), - _reverseOneSparsity(nullptr), - _reverseTwoSparsity(nullptr), - _jacobianSparsity(nullptr), - _hessianSparsity(nullptr), - _hessianSparsity2(nullptr) { - - } - - virtual void init() { - // validate the dynamic library - validate(); - - // load functions from the dynamic library - loadFunctions(); - } - - virtual void* loadFunction(const std::string& functionName, - bool required = true) = 0; - - virtual void validate() { - /** - * Check the data type - */ - void (*infoFunc)(const char** baseName, unsigned long*, unsigned long*, unsigned int*, unsigned int*); - infoFunc = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_INFO)); - - // local - const char* localBaseName = typeid (Base).name(); - std::string local = ModelCSourceGen::baseTypeName() + " " + localBaseName; - - // from dynamic library - const char* dynamicLibBaseName = nullptr; - unsigned int inSize = 0; - unsigned int outSize = 0; - (*infoFunc)(&dynamicLibBaseName, &_m, &_n, &inSize, &outSize); - - _in.resize(inSize); - _inHess.resize(inSize + 1); - _out.resize(outSize); - - CPPADCG_ASSERT_KNOWN(local == std::string(dynamicLibBaseName), - (std::string("Invalid data type in dynamic library. Expected '") + local - + "' but the library provided '" + dynamicLibBaseName + "'.").c_str()); - CPPADCG_ASSERT_KNOWN(inSize > 0, - "Invalid dimension received from the dynamic library."); - CPPADCG_ASSERT_KNOWN(outSize > 0, - "Invalid dimension received from the dynamic library."); - - _isLibraryReady = true; - } - - virtual void loadFunctions() { - _zero = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_FORWAD_ZERO, false)); - _forwardOne = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_FORWARD_ONE, false)); - _reverseOne = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_REVERSE_ONE, false)); - _reverseTwo = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_REVERSE_TWO, false)); - _jacobian = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_JACOBIAN, false)); - _hessian = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_HESSIAN, false)); - _sparseForwardOne = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_SPARSE_FORWARD_ONE, false)); - _sparseReverseOne = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_SPARSE_REVERSE_ONE, false)); - _sparseReverseTwo = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_SPARSE_REVERSE_TWO, false)); - _sparseJacobian = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_SPARSE_JACOBIAN, false)); - _sparseHessian = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_SPARSE_HESSIAN, false)); - _forwardOneSparsity = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_FORWARD_ONE_SPARSITY, false)); - _reverseOneSparsity = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_REVERSE_ONE_SPARSITY, false)); - _reverseTwoSparsity = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_REVERSE_TWO_SPARSITY, false)); - _jacobianSparsity = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_JACOBIAN_SPARSITY, false)); - _hessianSparsity = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_HESSIAN_SPARSITY, false)); - _hessianSparsity2 = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_HESSIAN_SPARSITY2, false)); - _atomicFunctions = reinterpret_cast(loadFunction(_name + "_" + ModelCSourceGen::FUNCTION_ATOMIC_FUNC_NAMES, true)); - - CPPADCG_ASSERT_KNOWN((_sparseForwardOne == nullptr) == (_forwardOneSparsity == nullptr), "Missing functions in the dynamic library"); - CPPADCG_ASSERT_KNOWN((_sparseForwardOne == nullptr) == (_forwardOne == nullptr), "Missing functions in the dynamic library"); - CPPADCG_ASSERT_KNOWN((_sparseReverseOne == nullptr) == (_reverseOneSparsity == nullptr), "Missing functions in the dynamic library"); - CPPADCG_ASSERT_KNOWN((_sparseReverseOne == nullptr) == (_reverseOne == nullptr), "Missing functions in the dynamic library"); - CPPADCG_ASSERT_KNOWN((_sparseReverseTwo == nullptr) == (_reverseTwoSparsity == nullptr), "Missing functions in the dynamic library"); - CPPADCG_ASSERT_KNOWN((_sparseReverseTwo == nullptr) == (_reverseTwo == nullptr), "Missing functions in the dynamic library"); - CPPADCG_ASSERT_KNOWN((_sparseJacobian == nullptr) || (_jacobianSparsity != nullptr), "Missing functions in the dynamic library"); - CPPADCG_ASSERT_KNOWN((_sparseHessian == nullptr) || (_hessianSparsity != nullptr), "Missing functions in the dynamic library"); - - /** - * Prepare the atomic functions argument - */ - const char** names; - unsigned long n; - (*_atomicFunctions)(&names, &n); - _atomic.resize(n); - - _atomicFuncArg.libModel = this; - _atomicFuncArg.forward = &atomicForward; - _atomicFuncArg.reverse = &atomicReverse; - - _missingAtomicFunctions = n; - } - - template - inline void loadSparsity(bool set_type, - VectorSet& s, - unsigned long nrows, unsigned long ncols, - unsigned long const* rows, unsigned long const* cols, - unsigned long nnz) { - s.resize(nrows * ncols, false); - - for (unsigned long i = 0; i < nnz; i++) { - s[rows[i] * ncols + cols[i]] = true; - } - } - - template - inline void loadSparsity(const std::set& set_type, - VectorSet& s, - unsigned long nrows, unsigned long ncols, - unsigned long const* rows, unsigned long const* cols, - unsigned long nnz) { - - // dimension size of result vector - s.resize(nrows); - - for (unsigned long i = 0; i < nnz; i++) { - s[rows[i]].insert(cols[i]); - } - } - - inline void createDenseFromSparse(const CppAD::vector& compressed, - unsigned long nrows, unsigned long ncols, - unsigned long const* rows, unsigned long const* cols, - unsigned long nnz, - Base* mat, size_t mat_size) const { - CPPADCG_ASSERT_KNOWN(mat_size == nrows * ncols, "Invalid matrix size"); - std::fill(mat, mat + mat_size, 0); - - for (size_t i = 0; i < nnz; i++) { - mat[rows[i] * ncols + cols[i]] = compressed[i]; - } - } - - virtual void modelLibraryClosed() { - _isLibraryReady = false; - _zero = nullptr; - _forwardOne = nullptr; - _reverseOne = nullptr; - _reverseTwo = nullptr; - _jacobian = nullptr; - _hessian = nullptr; - _sparseForwardOne = nullptr; - _sparseReverseOne = nullptr; - _sparseReverseTwo = nullptr; - _sparseJacobian = nullptr; - _sparseHessian = nullptr; - _forwardOneSparsity = nullptr; - _reverseOneSparsity = nullptr; - _reverseTwoSparsity = nullptr; - _jacobianSparsity = nullptr; - _hessianSparsity = nullptr; - _hessianSparsity2 = nullptr; - } - -private: - - template - inline bool addExternalFunction(ExtFunc& atomic, - const std::string& name) { - const char** names; - unsigned long n; - (*_atomicFunctions)(&names, &n); - - CPPADCG_ASSERT_UNKNOWN(_atomic.size() == n); - - for (unsigned long i = 0; i < n; i++) { - if (name == names[i]) { - if (_atomic[i] == nullptr) { - _missingAtomicFunctions--; - } else { - delete _atomic[i]; - } - _atomic[i] = new Wrapper(atomic); - return true; - } - } - return false; - } - - static int atomicForward(void* libModelIn, - int atomicIndex, - int q, - int p, - const Array tx[], - Array* ty) { - FunctorGenericModel* libModel = static_cast*> (libModelIn); - ExternalFunctionWrapper* externalFunc = libModel->_atomic[atomicIndex]; - - return externalFunc->forward(*libModel, q, p, tx, *ty); - } - - static int atomicReverse(void* libModelIn, - int atomicIndex, - int p, - const Array tx[], - Array* px, - const Array py[]) { - FunctorGenericModel* libModel = static_cast*> (libModelIn); - ExternalFunctionWrapper* externalFunc = libModel->_atomic[atomicIndex]; - - return externalFunc->reverse(*libModel, p, tx, *px, py); - } - - friend class LinuxDynamicLib; - friend class AtomicExternalFunctionWrapper; -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/functor_model_library.hpp b/ct_core/include/ct/external/cppad/cg/model/functor_model_library.hpp deleted file mode 100644 index 1173c5004..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/functor_model_library.hpp +++ /dev/null @@ -1,242 +0,0 @@ -#ifndef CPPAD_CG_FUNCTOR_MODEL_LIBRARY_INCLUDED -#define CPPAD_CG_FUNCTOR_MODEL_LIBRARY_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Abstract class used to load models - * - * @author Joao Leal - */ -template -class FunctorModelLibrary : public ModelLibrary { -protected: - std::set _modelNames; - unsigned long _version; // API version - void (*_onClose)(); - void (*_setThreadPoolDisabled)(int); - int (*_isThreadPoolDisabled)(); - void (*_setThreads)(unsigned int); - unsigned int (*_getThreads)(); - void (*_setSchedulerStrategy)(int); - int (*_getSchedulerStrategy)(); - void (*_setThreadPoolVerbose)(int v); - int (*_isThreadPoolVerbose)(); - void (*_setThreadPoolGuidedMaxWork)(float v); - float (*_getThreadPoolGuidedMaxWork)(); - void (*_setThreadPoolNumberOfTimeMeas)(unsigned int n); - unsigned int (*_getThreadPoolNumberOfTimeMeas)(); -public: - - virtual std::set getModelNames() override { - return _modelNames; - } - - /** - * Creates a new FunctorGenericModel object that can be used to evaluate - * the model. - * This object must be released by the user! - * - * @param modelName The model name. - * @return The model object (must be released by the user) or nullptr if - * no model exists with the provided name - */ - virtual FunctorGenericModel* model(const std::string& modelName) = 0; - - /** - * Provides the API version used to create the model library. - * - * @return the API version - */ - virtual unsigned long getAPIVersion() { - return _version; - } - - /** - * Provides a pointer to a function in the model library. - * - * @param functionName The name of the function in the dynamic library - * @param required Whether or not the function symbol must exist in the - * library. If the function is required and does not - * exist then the CppAD error handler is called, if it - * is not required and it does not exist then nullptr is - * return. - * @return A pointer to the function symbol in the dynamic library if it - * exists, nullptr otherwise. - * @throws CGException If there is a problem loading the function symbol - */ - virtual void* loadFunction(const std::string& functionName, - bool required = true) = 0; - - virtual void setThreadPoolDisabled(bool disabled) override { - if(_setThreadPoolDisabled != nullptr) { - (*_setThreadPoolDisabled)(disabled); - } - } - - virtual bool isThreadPoolDisabled() const { - if(_isThreadPoolDisabled != nullptr) { - return bool((*_isThreadPoolDisabled)()); - } - return true; - } - - virtual unsigned int getThreadNumber() const override { - if (_getThreads != nullptr) { - return (*_getThreads)(); - } - return 1; - } - - virtual void setThreadNumber(unsigned int n) override { - if (_setThreads != nullptr) { - (*_setThreads)(n); - } - } - - virtual ThreadPoolScheduleStrategy getThreadPoolSchedulerStrategy() const override { - if (_getSchedulerStrategy != nullptr) { - return ThreadPoolScheduleStrategy((*_getSchedulerStrategy)()); - } - return ThreadPoolScheduleStrategy::DYNAMIC; - } - - virtual void setThreadPoolSchedulerStrategy(ThreadPoolScheduleStrategy s) override { - if (_setSchedulerStrategy != nullptr) { - (*_setSchedulerStrategy)(int(s)); - } - } - - virtual void setThreadPoolVerbose(bool v) override { - if (_setThreadPoolVerbose != nullptr) { - (*_setThreadPoolVerbose)(int(v)); - } - } - - virtual bool isThreadPoolVerbose() const override { - if (_isThreadPoolVerbose != nullptr) { - return bool((*_isThreadPoolVerbose)()); - } - return false; - } - - virtual void setThreadPoolGuidedMaxWork(float v) override { - if (_setThreadPoolGuidedMaxWork != nullptr) { - (*_setThreadPoolGuidedMaxWork)(v); - } - } - - virtual float getThreadPoolGuidedMaxWork() const override { - if (_getThreadPoolGuidedMaxWork != nullptr) { - return (*_getThreadPoolGuidedMaxWork)(); - } - return 1.0; - } - - virtual void setThreadPoolNumberOfTimeMeas(unsigned int n) override { - if (_setThreadPoolNumberOfTimeMeas != nullptr) { - (*_setThreadPoolNumberOfTimeMeas)(n); - } - } - - virtual unsigned int getThreadPoolNumberOfTimeMeas() const override { - if (_getThreadPoolNumberOfTimeMeas != nullptr) { - return (*_getThreadPoolNumberOfTimeMeas)(); - } - return 0; - } - - inline virtual ~FunctorModelLibrary() { - } - -protected: - FunctorModelLibrary() : - _version(0), // not really required (but it avoids warnings) - _onClose(nullptr), - _setThreadPoolDisabled(nullptr), - _isThreadPoolDisabled(nullptr), - _setThreads(nullptr), - _getThreads(nullptr), - _setSchedulerStrategy(nullptr), - _getSchedulerStrategy(nullptr), - _setThreadPoolVerbose(nullptr), - _isThreadPoolVerbose(nullptr), - _setThreadPoolGuidedMaxWork(nullptr), - _getThreadPoolGuidedMaxWork(nullptr), - _setThreadPoolNumberOfTimeMeas(nullptr), - _getThreadPoolNumberOfTimeMeas(nullptr) { - } - - inline void validate() { - /** - * Check the version - */ - unsigned long (*versionFunc)(); - versionFunc = reinterpret_cast (loadFunction(ModelLibraryCSourceGen::FUNCTION_VERSION)); - - _version = (*versionFunc)(); - if (ModelLibraryCSourceGen::API_VERSION != _version) - throw CGException("The API version of the dynamic library (", _version, - ") is incompatible with the current version (", - ModelLibraryCSourceGen::API_VERSION, ")"); - - /** - * Load the list of models - */ - void (*modelsFunc)(char const *const**, int*); - modelsFunc = reinterpret_cast (loadFunction(ModelLibraryCSourceGen::FUNCTION_MODELS)); - - char const*const* model_names = nullptr; - int model_count; - (*modelsFunc)(&model_names, &model_count); - - for (int i = 0; i < model_count; i++) { - _modelNames.insert(model_names[i]); - } - - /** - * Load the the on close function - */ - _onClose = reinterpret_cast (loadFunction(ModelLibraryCSourceGen::FUNCTION_ONCLOSE, false)); - - /** - * Thread pool related functions - */ - _setThreadPoolDisabled = reinterpret_cast (loadFunction(ModelLibraryCSourceGen::FUNCTION_SETTHREADPOOLDISABLED, false)); - _isThreadPoolDisabled = reinterpret_cast (loadFunction(ModelLibraryCSourceGen::FUNCTION_ISTHREADPOOLDISABLED, false)); - _setThreads = reinterpret_cast (loadFunction(ModelLibraryCSourceGen::FUNCTION_SETTHREADS, false)); - _getThreads = reinterpret_cast (loadFunction(ModelLibraryCSourceGen::FUNCTION_GETTHREADS, false)); - _setSchedulerStrategy = reinterpret_cast (this->loadFunction(ModelLibraryCSourceGen::FUNCTION_SETTHREADSCHEDULERSTRAT, false)); - _getSchedulerStrategy = reinterpret_cast (this->loadFunction(ModelLibraryCSourceGen::FUNCTION_GETTHREADSCHEDULERSTRAT, false)); - _setThreadPoolVerbose = reinterpret_cast (this->loadFunction(ModelLibraryCSourceGen::FUNCTION_SETTHREADPOOLVERBOSE, false)); - _isThreadPoolVerbose = reinterpret_cast (this->loadFunction(ModelLibraryCSourceGen::FUNCTION_ISTHREADPOOLVERBOSE, false)); - _setThreadPoolGuidedMaxWork = reinterpret_cast (this->loadFunction(ModelLibraryCSourceGen::FUNCTION_SETTHREADPOOLGUIDEDMAXGROUPWORK, false)); - _getThreadPoolGuidedMaxWork = reinterpret_cast (this->loadFunction(ModelLibraryCSourceGen::FUNCTION_GETTHREADPOOLGUIDEDMAXGROUPWORK, false)); - _setThreadPoolNumberOfTimeMeas = reinterpret_cast (this->loadFunction(ModelLibraryCSourceGen::FUNCTION_SETTHREADPOOLNUMBEROFTIMEMEAS, false)); - _getThreadPoolNumberOfTimeMeas = reinterpret_cast (this->loadFunction(ModelLibraryCSourceGen::FUNCTION_GETTHREADPOOLNUMBEROFTIMEMEAS, false)); - - if(_setThreads != nullptr) { - (*_setThreads)(std::thread::hardware_concurrency()); - } - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/generic_model.hpp b/ct_core/include/ct/external/cppad/cg/model/generic_model.hpp deleted file mode 100644 index f930b44e6..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/generic_model.hpp +++ /dev/null @@ -1,804 +0,0 @@ -#ifndef CPPAD_CG_GENERIC_MODEL_INCLUDED -#define CPPAD_CG_GENERIC_MODEL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Abstract class used to execute a generated model - * - * @author Joao Leal - */ -template -class GenericModel { -protected: - CGAtomicGenericModel* _atomic; - // whether or not to evaluate forward mode of atomics during a reverse sweep - bool _evalAtomicForwardOne4CppAD; -public: - - GenericModel() : - _atomic(nullptr), - _evalAtomicForwardOne4CppAD(true) { - } - - inline virtual ~GenericModel() { - delete _atomic; - } - - /** - * Provides the name for this model. - * - * @return The model name - */ - virtual const std::string& getName() const = 0; - - - /** - * Determines whether or not the Jacobian sparsity pattern can be requested. - * - * @return true if it is possible to request the Jacobian sparsity pattern - */ - virtual bool isJacobianSparsityAvailable() = 0; - - // Jacobian sparsity - virtual std::vector > JacobianSparsitySet() = 0; - virtual std::vector JacobianSparsityBool() = 0; - virtual void JacobianSparsity(std::vector& rows, - std::vector& cols) = 0; - - /** - * Determines whether or not the sparsity pattern for the weighted sum of - * the Hessians can be requested. - * - * @return true if it is possible to request the parsity pattern for the - * weighted sum of the Hessians - */ - virtual bool isHessianSparsityAvailable() = 0; - - /** - * Provides the sparsity of the sum of the hessian for each dependent - * variable. - * - * @return The sparsity - */ - virtual std::vector > HessianSparsitySet() = 0; - virtual std::vector HessianSparsityBool() = 0; - virtual void HessianSparsity(std::vector& rows, - std::vector& cols) = 0; - - /** - * Determines whether or not the sparsity pattern for the Hessian - * associated with a dependent variable can be requested. - * - * @return true if it is possible to request the parsity pattern for the - * Hessians - */ - virtual bool isEquationHessianSparsityAvailable() = 0; - - /** - * Provides the sparsity of the hessian for a dependent variable - * - * @param i The index of the dependent variable - * @return The sparsity - */ - virtual std::vector > HessianSparsitySet(size_t i) = 0; - virtual std::vector HessianSparsityBool(size_t i) = 0; - virtual void HessianSparsity(size_t i, - std::vector& rows, - std::vector& cols) = 0; - - /** - * Provides the number of independent variables. - * - * @return The number of independent variables - */ - virtual size_t Domain() const = 0; - - /** - * Provides the number of dependent variables. - * - * @return The number of dependent variables. - */ - virtual size_t Range() const = 0; - - /** - * Defines a CppAD atomic function to be used as an external function - * by the compiled code. - * It should match an external function name previously provided to - * create the source. - * - * @param atomic The atomic function. This object must only be deleted - * after the model. - * @return true if the atomic function is required by the model, false - * if it will never be used. - */ - virtual bool addAtomicFunction(atomic_base& atomic) = 0; - - /** - * Defines a generic model to be used as an external function by the - * compiled code. - * It should match an external function name previously provided to - * create the source. This form should be preferred over - * ::addAtomicFunction whenever possible. - * - * @param atomic The generic model. This object must only be deleted - * after the model. - * @return true if the external function is required by the model, false - * if it will never be used. - */ - virtual bool addExternalModel(GenericModel& atomic) = 0; - - /** - * Defines whether or not to evaluate a forward mode of an atomic - * functions during a reverse sweep so that CppAD checks validate OK. - * If this model is not used within CppAD then it should be set to false. - * - * @param evalForwardOne4CppAD true to perform the forward mode, - * false to ignore it - */ - inline void setAtomicEvalForwardOne4CppAD(bool evalForwardOne4CppAD) { - _evalAtomicForwardOne4CppAD = evalForwardOne4CppAD; - } - - inline bool isAtomicEvalForwardOne4CppAD() const { - return _evalAtomicForwardOne4CppAD; - } - - /*********************************************************************** - * Forward zero - **********************************************************************/ - - /** - * Determines whether or not the model evaluation (zero-order forward mode) - * can be requested. - * - * @return true if it is possible to evaluate the model - */ - virtual bool isForwardZeroAvailable() = 0; - - /** - * Evaluates the dependent model variables (zero-order). - * This method considers that the generic model was prepared - * with a single array for the independent variables (the default - * behavior). - * - * @param x The independent variable vector - * @return The dependent variable vector - */ - template - inline VectorBase ForwardZero(const VectorBase& x) { - VectorBase dep(Range()); - this->ForwardZero(&x[0], x.size(), &dep[0], dep.size()); - return dep; - } - - virtual void ForwardZero(const CppAD::vector& vx, - CppAD::vector& vy, - const CppAD::vector &tx, - CppAD::vector& ty) = 0; - - /** - * Evaluates the dependent model variables (zero-order). - * This method considers that the generic model was prepared - * using a single array for the independent variables (the default - * behavior). - * - * @param x The independent variable vector - * @param dep The dependent variable vector - */ - template - inline void ForwardZero(const VectorBase& x, - VectorBase& dep) { - dep.resize(Range()); - this->ForwardZero(&x[0], x.size(), &dep[0], dep.size()); - } - - virtual void ForwardZero(const Base* x, size_t x_size, - Base* dep, size_t dep_size) = 0; - - /** - * Determines the dependent variable values using a variable number of - * independent variable arrays. - * This method can be useful if the generic model was prepared - * considering that the independent variables are provided by several - * arrays. - * - * @param x Contains the several independent variable vectors - * @param dep The values of the dependent variables - * @param dep_size The number of dependent variables - */ - virtual void ForwardZero(const std::vector &x, - Base* dep, size_t dep_size) = 0; - - /*********************************************************************** - * Dense Jacobian - **********************************************************************/ - - /** - * Determines whether or not the dense Jacobian evaluation can be - * requested. - * - * @return true if it is possible to evaluate the dense Jacobian - */ - virtual bool isJacobianAvailable() = 0; - - template - inline VectorBase Jacobian(const VectorBase& x) { - VectorBase jac(Range() * Domain()); - Jacobian(&x[0], x.size(), &jac[0], jac.size()); - return jac; - } - - template - inline void Jacobian(const VectorBase& x, - VectorBase& jac) { - jac.resize(Range() * Domain()); - Jacobian(&x[0], x.size(), &jac[0], jac.size()); - } - - virtual void Jacobian(const Base* x, size_t x_size, - Base* jac, size_t jac_size) = 0; - - /*********************************************************************** - * Dense Hessian - **********************************************************************/ - - /** - * Determines whether or not the dense evaluation of the weigthed sum of - * the Hessians can be requested. - * - * @return true if it is possible to evaluate the dense weigthed sum of - * the Hessians - */ - virtual bool isHessianAvailable() = 0; - - template - inline VectorBase Hessian(const VectorBase& x, - const VectorBase& w) { - VectorBase hess(Domain() * Domain()); - this->Hessian(x, w, hess); - return hess; - } - - /// calculate Hessian for one component of f - - template - inline VectorBase Hessian(const VectorBase& x, - size_t i) { - CPPADCG_ASSERT_KNOWN(i < Range(), "Invalid equation index"); - - VectorBase w(Range()); - w[i] = 1.0; - VectorBase hess(Domain() * Domain()); - this->Hessian(x, w, hess); - return hess; - } - - template - inline void Hessian(const VectorBase& x, - const VectorBase& w, - VectorBase& hess) { - this->Hessian(&x[0], x.size(), &w[0], w.size(), &hess[0]); - } - - virtual void Hessian(const Base* x, size_t x_size, - const Base* w, size_t w_size, - Base* hess) = 0; - - /*********************************************************************** - * Forward one - **********************************************************************/ - - /** - * Determines whether or not the first-order forward mode dense - * methods can be called. - * - * @return true if it is possible to evaluate the first-order forward mode - * using the dense vector format - */ - virtual bool isForwardOneAvailable() = 0; - - /** - * Computes results during a forward mode sweep. - * Computes the first-order Taylor coefficients for dependent variables - * relative to a single independent variable. - * This method can be used during the evaluation of the jacobian when - * the model is used through a user defined external/atomic AD function. - * @warning do not used it as a generic forward mode function! - * - * @param tx The Taylor coefficients of the independent variables - * @return The Taylor coefficients of the dependent variables - */ - template - inline VectorBase ForwardOne(const VectorBase& tx) { - size_t m = Range(); - const size_t k = 1; - VectorBase ty((k + 1) * m); - - this->ForwardOne(tx, ty); - - VectorBase dy(m); - for (size_t i = 0; i < m; i++) { - dy[i] = ty[i * (k + 1) + k]; - } - - return dy; - } - - /** - * Computes results during a forward mode sweep. - * Computes the first-order Taylor coefficients for dependent variables - * relative to a single independent variable. - * This method can be used during the evaluation of the jacobian when - * the model is used through a user defined external/atomic AD function. - * @warning do not used it as a generic forward mode function! - * - * @param tx The Taylor coefficients of the independent variables - * @param ty The Taylor coefficients of the dependent variables - */ - template - inline void ForwardOne(const VectorBase& tx, - VectorBase& ty) { - this->ForwardOne(&tx[0], tx.size(), &ty[0], ty.size()); - } - - /** - * Computes results during a forward mode sweep. - * Computes the first-order Taylor coefficients for dependent variables - * relative to a single independent variable. - * This method can be used during the evaluation of the jacobian when - * the model is used through a user defined external/atomic AD function. - * @warning do not used it as a generic forward mode function! - * - * @param tx The Taylor coefficients of the independent variables - * @param tx_size The size of tx - * @param ty The Taylor coefficients of the dependent variables - * @param ty_size The size of ty - */ - virtual void ForwardOne(const Base tx[], size_t tx_size, - Base ty[], size_t ty_size) = 0; - - /** - * Determines whether or not the first-order forward mode sparse - * method can be called. - * - * @return true if it is possible to evaluate the first-order forward mode - * using the sparse vector format - */ - virtual bool isSparseForwardOneAvailable() = 0; - - /** - * Computes results during a first-order forward mode sweep, the - * first-order Taylor coefficients for dependent variables relative to - * a single independent variable. - * This method can be used during the evaluation of the jacobian when - * the model is used through a user defined external/atomic AD function. - * This method version avoids some data copies and can be more efficient. - * @warning do not used it as a generic forward mode function! - * - * @param x independent variable vector - * @param x_size size of the independent variable vector - * @param tx1Nnz the number of non-zeros of the directional derivatives - * of the independent variables (seed directions) - * @param idx the locations of the non-zero values the partial - * derivatives of the dependent variables (seeds) - * @param tx1 the non-zero values of the partial derivatives of the - * dependent variables (seeds) - * @param ty1 - * @param ty1_size - */ - virtual void ForwardOne(const Base x[], size_t x_size, - size_t tx1Nnz, const size_t idx[], const Base tx1[], - Base ty1[], size_t ty1_size) = 0; - - /*********************************************************************** - * Reverse one - **********************************************************************/ - - /** - * Determines whether or not the first-order reverse mode dense - * methods can be called. - * - * @return true if it is possible to evaluate the first-order reverse mode - * using the dense vector format - */ - virtual bool isReverseOneAvailable() = 0; - - /** - * Computes results during a reverse mode sweep (adjoints or partial - * derivatives of independent variables) for the evaluation of the - * jacobian when the model is used through a user defined - * external/atomic AD function. - * @warning do not used it as a generic reverse mode function! - * - * @param tx - * @param ty - * @param py - * @return px - */ - template - inline VectorBase ReverseOne(const VectorBase& tx, - const VectorBase& ty, - const VectorBase& py) { - const size_t k = 0; - VectorBase px((k + 1) * Domain()); - this->ReverseOne(tx, ty, px, py); - return px; - } - - /** - * Computes results during a reverse mode sweep (adjoints or partial - * derivatives of independent variables) for the evaluation of the - * jacobian when the model is used through a user defined - * external/atomic AD function. - * @warning do not used it as a generic reverse mode function! - * - * @param tx - * @param ty - * @param px - * @param py - */ - template - inline void ReverseOne(const VectorBase& tx, - const VectorBase& ty, - VectorBase& px, - const VectorBase& py) { - this->ReverseOne(&tx[0], tx.size(), - &ty[0], ty.size(), - &px[0], px.size(), - &py[0], py.size()); - } - - /** - * Determines whether or not the first-order reverse mode sparse - * method can be called. - * - * @return true if it is possible to evaluate the first-order reverse mode - * using the sparse vector format - */ - virtual bool isSparseReverseOneAvailable() = 0; - - /** - * Computes results during a reverse mode sweep (adjoints or partial - * derivatives of independent variables) for the evaluation of the - * jacobian when the model is used through a user defined - * external/atomic AD function. - * @warning do not used it as a generic reverse mode function! - * - * @param tx - * @param ty - * @param px - * @param py - */ - virtual void ReverseOne(const Base tx[], size_t tx_size, - const Base ty[], size_t ty_size, - Base px[], size_t px_size, - const Base py[], size_t py_size) = 0; - - /** - * Computes results during a reverse mode sweep (adjoints or partial - * derivatives of independent variables) for the evaluation of the - * jacobian when the model is used through a user defined - * external/atomic AD function. - * This method version avoids some data copies and can be more efficient. - * @warning do not used it as a generic reverse mode function! - * - * @param x independent variable vector - * @param x_size size of the independent variable vector - * @param px partial derivatives of the independent variables - * @param px_size the size of the partial derivatives of the independent - * variables (should be same as x_size) - * @param pyNnz the number of non-zeros of the partial derivatives of - * the dependent variables (weight functionals) - * @param idx the locations of the non-zero values the partial - * derivatives of the dependent variables (weight functionals) - * @param py the non-zero values of the partial derivatives of the - * dependent variables (weight functionals) - */ - virtual void ReverseOne(const Base x[], size_t x_size, - Base px[], size_t px_size, - size_t pyNnz, const size_t idx[], const Base py[]) = 0; - - /*********************************************************************** - * Reverse two - **********************************************************************/ - - /** - * Determines whether or not the second-order reverse mode dense - * methods can be called. - * - * @return true if it is possible to evaluate the second-order reverse mode - * using the dense vector format - */ - virtual bool isReverseTwoAvailable() = 0; - - /** - * Computes second-order results during a reverse mode sweep (p = 2). - * This method can be used during the evaluation of the hessian when - * the model is used through a user defined external/atomic AD function. - * @warning do not used it as a generic reverse mode function! - * @warning only the values for px[j * (k+1)] are defined, since - * px[j * (k+1) + 1] is not used during the hessian evaluation. - * - * @param tx - * @param ty - * @param py - * @return px - */ - template - inline VectorBase ReverseTwo(const VectorBase& tx, - const VectorBase& ty, - const VectorBase& py) { - const size_t k = 1; - VectorBase px((k + 1) * Domain()); - this->ReverseTwo(tx, ty, px, py); - return px; - } - - /** - * Computes second-order results during a reverse mode sweep (p = 2). - * This method can be used during the evaluation of the hessian when - * the model is used through a user defined external/atomic AD function. - * @warning do not used it as a generic reverse mode function! - * @warning only the values for px[j * (k+1)] are defined, since - * px[j * (k+1) + 1] is not used during the hessian evaluation. - * - * @param tx - * @param ty - * @param px - * @param py - */ - template - inline void ReverseTwo(const VectorBase& tx, - const VectorBase& ty, - VectorBase& px, - const VectorBase& py) { - this->ReverseTwo(&tx[0], tx.size(), - &ty[0], ty.size(), - &px[0], px.size(), - &py[0], py.size()); - } - - /** - * Determines whether or not the second-order reverse mode sparse - * methods can be called. - * - * @return true if it is possible to evaluate the second-order reverse mode - * using the sparse vector format - */ - virtual bool isSparseReverseTwoAvailable() = 0; - - /** - * Computes second-order results during a reverse mode sweep (p = 2). - * This method can be used during the evaluation of the hessian when - * the model is used through a user defined external/atomic AD function. - * @warning do not used it as a generic reverse mode function! - * @warning only the values for px[j * (k+1)] are defined, since - * px[j * (k+1) + 1] is not used during the hessian evaluation. - * - * @param tx - * @param ty - * @param px - * @param py - */ - virtual void ReverseTwo(const Base tx[], size_t tx_size, - const Base ty[], size_t ty_size, - Base px[], size_t px_size, - const Base py[], size_t py_size) = 0; - /** - * Computes second-order results during a reverse mode sweep (p = 2). - * This method can be used during the evaluation of the hessian when - * the model is used through a user defined external AD function. - * This method version avoids some data copies and can be more efficient. - * @warning do not used it as a generic reverse mode function! - * - * @param x independent variable vector - * @param x_size size of the independent variable vector - * @param tx1Nnz the number of non-zeros of the first-order Taylor - * coefficients of the independents - * @param idx the locations of the non-zero values of the first-order - * Taylor coefficients of the independents - * @param tx1 the values of the non-zero first-order Taylor coefficients - * of the independents - * @param px2 second-order partials of the independents - * @param px2_size size of px2 - * (should be the number of independent variables) - * @param py2 second-order partials of the dependents - * @param py2_size size of py2 - * (should be the number of dependent variables) - */ - virtual void ReverseTwo(const Base x[], size_t x_size, - size_t tx1Nnz, const size_t idx[], const Base tx1[], - Base px2[], size_t px2_size, - const Base py2[], size_t py2_size) = 0; - - /*********************************************************************** - * Sparse Jacobians - **********************************************************************/ - - /** - * Determines whether or not the sparse Jacobian evaluation methods can - * be called. - * - * @return true if it is possible to evaluate the sparse Jacobian - */ - virtual bool isSparseJacobianAvailable() = 0; - - /** - * Calculates a Jacobian using sparse methods and saves it into a dense - * format: - * \f[ jac[ i n + j ] = \frac{\partial F_i( x ) }{\partial x_j } \f] - * \f$ i = 0 , \ldots , m - 1 \f$ and \f$j = 0 , \ldots , n - 1 \f$. - * - * @param x independent variable vector - * @return a dense jacobian - */ - template - inline VectorBase SparseJacobian(const VectorBase& x) { - VectorBase jac(Range() * Domain()); - SparseJacobian(x, jac); - return jac; - } - - /** - * Calculates a Jacobian using sparse methods and saves it into a dense - * format: - * \f[ jac[ i n + j ] = \frac{\partial F_i( x ) }{\partial x_j } \f] - * \f$ i = 0 , \ldots , m - 1 \f$ and \f$j = 0 , \ldots , n - 1 \f$. - * - * @param x independent variable vector - * @param jac a vector where the dense jacobian will be placed - */ - template - inline void SparseJacobian(const VectorBase& x, - VectorBase& jac) { - jac.resize(Range() * Domain()); - SparseJacobian(&x[0], x.size(), &jac[0], jac.size()); - } - - /** - * Calculates a Jacobian using sparse methods and saves it into a dense - * format: - * \f[ jac[ i n + j ] = \frac{\partial F_i( x ) }{\partial x_j } \f] - * \f$ i = 0 , \ldots , m - 1 \f$ and \f$j = 0 , \ldots , n - 1 \f$. - * - * @param x independent variable array (must have n elements) - * @param x_size the size of the array (for verification purposes only) - * @param jac an array where the dense jacobian will be placed (must be allocated with at least m * n elements) - * @param jac_size the jacobian array size (for verification purposes only) - */ - virtual void SparseJacobian(const Base* x, size_t x_size, - Base* jac, size_t jac_size) = 0; - - virtual void SparseJacobian(const std::vector &x, - std::vector& jac, - std::vector& row, - std::vector& col) = 0; - - virtual void SparseJacobian(const Base* x, size_t x_size, - Base* jac, - size_t const** row, - size_t const** col, - size_t nnz) = 0; - - /** - * Determines the sparse Jacobian using a variable number of independent - * variable arrays. This method can be useful if the generic model was - * prepared considering that the independent variables are provided - * by several arrays. - * - * @param x Contains the several independent variable vectors - * @param jac The values of the sparse Jacobian in the order provided by - * row and col - * @param row The row indices of the Jacobian values - * @param col The column indices of the Jacobian values - * @param nnz The total number of non-zero elements - */ - virtual void SparseJacobian(const std::vector& x, - Base* jac, - size_t const** row, - size_t const** col, - size_t nnz) = 0; - - /*********************************************************************** - * Sparse Hessians - **********************************************************************/ - - /** - * Determines whether or not the sparse evaluation of the weigthed sum of - * the Hessians methods can be called. - * - * @return true if it is possible to evaluate the sparse weigthed sum of - * the Hessians - */ - virtual bool isSparseHessianAvailable() = 0; - - template - inline VectorBase SparseHessian(const VectorBase& x, - const VectorBase& w) { - VectorBase hess(Domain() * Domain()); - SparseHessian(x, w, hess); - return hess; - } - - template - inline void SparseHessian(const VectorBase& x, - const VectorBase& w, - VectorBase& hess) { - hess.resize(Domain() * Domain()); - SparseHessian(&x[0], x.size(), &w[0], w.size(), &hess[0], hess.size()); - } - - virtual void SparseHessian(const Base* x, size_t x_size, - const Base* w, size_t w_size, - Base* hess, size_t hess_size) = 0; - - virtual void SparseHessian(const std::vector &x, - const std::vector &w, - std::vector& hess, - std::vector& row, - std::vector& col) = 0; - - virtual void SparseHessian(const Base* x, size_t x_size, - const Base* w, size_t w_size, - Base* hess, - size_t const** row, - size_t const** col, - size_t nnz) = 0; - - /** - * Determines the sparse Hessian using a variable number of independent - * variable arrays. This method can be useful if the generic model was - * prepared considering that the independent variables are provided - * by several arrays. - * - * @param x Contains the several independent variable vectors - * @param w The equation multipliers - * @param w_size The number of equations - * @param hess The values of the sparse hessian in the order provided by - * row and col - * @param row The row indices of the hessian values - * @param col The column indices of the hessian values - * @param nnz The total number of non-zero elements - */ - virtual void SparseHessian(const std::vector& x, - const Base* w, size_t w_size, - Base* hess, - size_t const** row, - size_t const** col, - size_t nnz) = 0; - - /** - * Provides a wrapper for this compiled model allowing it to be used as - * an atomic function. The model must not be deleted while the atomic - * function is in use. - * - * @return an atomic function wrapper for this model - */ - virtual CGAtomicGenericModel& asAtomic() { - if (_atomic == nullptr) { - _atomic = new CGAtomicGenericModel(*this); - } - return *_atomic; - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/generic_model_external_function_wrapper.hpp b/ct_core/include/ct/external/cppad/cg/model/generic_model_external_function_wrapper.hpp deleted file mode 100644 index a12991ce3..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/generic_model_external_function_wrapper.hpp +++ /dev/null @@ -1,105 +0,0 @@ -#ifndef CPPAD_CG_GENERIC_MODEL_EXTERNAL_FUNCTION_WRAPPER_INCLUDED -#define CPPAD_CG_GENERIC_MODEL_EXTERNAL_FUNCTION_WRAPPER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -class GenericModelExternalFunctionWrapper : public ExternalFunctionWrapper { -private: - GenericModel* model_; -public: - - inline GenericModelExternalFunctionWrapper(GenericModel& model) : - model_(&model) { - - } - - virtual bool forward(FunctorGenericModel& libModel, - int q, - int p, - const Array tx[], - Array& ty) { - CPPADCG_ASSERT_KNOWN(!tx[0].sparse, "independent array must be dense"); - const Base* x = static_cast (tx[0].data); - - CPPADCG_ASSERT_KNOWN(!ty.sparse, "dependent array must be dense"); - Base* y = static_cast (ty.data); - - if (p == 0) { - model_->ForwardZero(x, tx[0].size, y, ty.size); - return true; - - } else if (p == 1) { - CPPADCG_ASSERT_KNOWN(tx[1].sparse, "independent Taylor array must be sparse"); - Base* tx1 = static_cast (tx[1].data); - - model_->ForwardOne(x, tx[0].size, - tx[1].nnz, tx[1].idx, tx1, - y, ty.size); - return true; - } - - return false; - } - - virtual bool reverse(FunctorGenericModel& libModel, - int p, - const Array tx[], - Array& px, - const Array py[]) { - CPPADCG_ASSERT_KNOWN(!tx[0].sparse, "independent array must be dense"); - const Base* x = static_cast (tx[0].data); - - CPPADCG_ASSERT_KNOWN(!px.sparse, "independent partials array must be dense"); - Base* pxb = static_cast (px.data); - - if (p == 0) { - CPPADCG_ASSERT_KNOWN(py[0].sparse, "dependent partials array must be sparse"); - Base* pyb = static_cast (py[0].data); - - model_->ReverseOne(x, tx[0].size, - pxb, px.size, - py[0].nnz, py[0].idx, pyb); - return true; - - } else if (p == 1) { - CPPADCG_ASSERT_KNOWN(tx[1].sparse, "independent array must be sparse"); - const Base* tx1 = static_cast (tx[1].data); - CPPADCG_ASSERT_KNOWN(py[0].sparse, "dependent partials array must be sparse"); - CPPADCG_ASSERT_KNOWN(py[0].nnz == 0, "first order dependent partials must be zero"); - CPPADCG_ASSERT_KNOWN(!py[1].sparse, "independent partials array must be dense"); - Base* py2 = static_cast (py[1].data); - - model_->ReverseTwo(x, tx[0].size, - tx[1].nnz, tx[1].idx, tx1, - pxb, px.size, - py2, py[1].size); - return true; - } - - return false; - } - - inline virtual ~GenericModelExternalFunctionWrapper() { - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/llvm.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/llvm.hpp deleted file mode 100644 index cfa73ba78..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/llvm.hpp +++ /dev/null @@ -1,32 +0,0 @@ -#ifndef CPPAD_CG_LLVM_INCLUDED -#define CPPAD_CG_LLVM_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#ifdef LLVM_VERSION_MAJOR - -#if LLVM_VERSION_MAJOR==3 && LLVM_VERSION_MINOR==2 -#include -#elif LLVM_VERSION_MAJOR==3 && (LLVM_VERSION_MINOR==3 || LLVM_VERSION_MINOR==4) -#include -#elif LLVM_VERSION_MAJOR==3 && LLVM_VERSION_MINOR==6 -#include -#elif LLVM_VERSION_MAJOR==3 && LLVM_VERSION_MINOR==8 -#include -#endif - -#endif - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/llvm_base_model_library_processor.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/llvm_base_model_library_processor.hpp deleted file mode 100644 index a09bdac6a..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/llvm_base_model_library_processor.hpp +++ /dev/null @@ -1,112 +0,0 @@ -#ifndef CPPAD_CG_LLVM_BASE_MODEL_LIBRARY_PROCESSOR_INCLUDED -#define CPPAD_CG_LLVM_BASE_MODEL_LIBRARY_PROCESSOR_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Base class for the creation of a model libraries using LLVM. - * - * @author Joao Leal - */ -template -class LlvmBaseModelLibraryProcessor : public ModelLibraryProcessor { -public: - - inline LlvmBaseModelLibraryProcessor(ModelLibraryCSourceGen& modelLibraryHelper) : - ModelLibraryProcessor(modelLibraryHelper) { - } - - inline virtual ~LlvmBaseModelLibraryProcessor() { - } - -protected: - - static std::string findInternalClangCHeaders(const std::string& version, - const std::string& resourceDir) { - // check existing paths - for (std::string path : explode(resourceDir, " ")) { - if (system::isFile(system::createPath(path, system::createPath("include", "stddef.h")))) { - return ""; // no need to add anything - } - } - -#ifdef CPPAD_CG_SYSTEM_LINUX - std::string clangHeaders = "/usr/lib/clang/" + version + "/include"; - if (system::isDirectory(clangHeaders)) { - return clangHeaders; // found them - } -#endif - - // failed to locate headers (hope they are not needed...) - return ""; - } - - const std::set& createBitCode(ClangCompiler& clang, - const std::string& version) { - // backup output format so that it can be restored - OStreamConfigRestore coutb(std::cout); - - if (clang.getVersion() != version) { - auto expected = ClangCompiler::parseVersion(version); - auto execVersion = ClangCompiler::parseVersion(clang.getVersion()); - bool error = expected.size() > execVersion.size(); - if (!error) { - for (size_t i = 0; i < expected.size(); ++i) { - if (expected[i] != execVersion[i]) { - error = true; - break; - } - } - } - if (error) { - throw CGException("Expected a clang with version '", version, "' but found version '", clang.getVersion(), "'"); - } - } - - const std::map*>& models = this->modelLibraryHelper_->getModels(); - try { - /** - * generate bit code - */ - for (const auto& p : models) { - const std::map& modelSources = this->getSources(*p.second); - - this->modelLibraryHelper_->startingJob("", JobTimer::COMPILING_FOR_MODEL); - clang.generateLLVMBitCode(modelSources, this->modelLibraryHelper_); - this->modelLibraryHelper_->finishedJob(); - } - - const std::map& sources = this->getLibrarySources(); - clang.generateLLVMBitCode(sources, this->modelLibraryHelper_); - - const std::map& customSource = this->modelLibraryHelper_->getCustomSources(); - clang.generateLLVMBitCode(customSource, this->modelLibraryHelper_); - } catch (...) { - clang.cleanup(); - throw; - } - - return clang.getBitCodeFiles(); - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/llvm_model.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/llvm_model.hpp deleted file mode 100644 index 1d07f1bdf..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/llvm_model.hpp +++ /dev/null @@ -1,75 +0,0 @@ -#ifndef CPPAD_CG_LLVM_MODEL_INCLUDED -#define CPPAD_CG_LLVM_MODEL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Useful class to call the JIT'ed models with LLVM. - * - * @author Joao Leal - */ -template -class LlvmModel : public FunctorGenericModel { -protected: - /// the dynamic library - LlvmModelLibrary* _dynLib; - -public: - - LlvmModel(const LlvmModel&) = delete; - LlvmModel& operator=(const LlvmModel&) = delete; - - virtual ~LlvmModel() { - if (_dynLib != nullptr) { - _dynLib->destroyed(this); - } - } - -protected: - - /** - * Creates a new model - * - * @param name The model name - */ - LlvmModel(LlvmModelLibrary* dynLib, - const std::string& name) : - FunctorGenericModel(name), - _dynLib(dynLib) { - - CPPADCG_ASSERT_UNKNOWN(_dynLib != nullptr); - - this->init(); - } - - virtual void* loadFunction(const std::string& functionName, bool required = true) override { - return _dynLib->loadFunction(functionName, required); - } - - virtual void modelLibraryClosed() override { - _dynLib = nullptr; - FunctorGenericModel::modelLibraryClosed(); - } - - friend class LlvmModelLibrary; -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/llvm_model_library.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/llvm_model_library.hpp deleted file mode 100644 index 178b986af..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/llvm_model_library.hpp +++ /dev/null @@ -1,74 +0,0 @@ -#ifndef CPPAD_CG_LLVM_MODEL_LIBRARY_INCLUDED -#define CPPAD_CG_LLVM_MODEL_LIBRARY_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -class LlvmModel; - -/** - * Abstract class used to load JIT'ed models by LLVM - * - * @author Joao Leal - */ -template -class LlvmModelLibrary : public FunctorModelLibrary { -protected: - std::set*> _models; -public: - virtual LlvmModel* model(const std::string& modelName) override { - typename std::set::const_iterator it = this->_modelNames.find(modelName); - if (it == this->_modelNames.end()) { - return nullptr; - } - LlvmModel* m = new LlvmModel (this, modelName); - _models.insert(m); - return m; - } - - inline virtual ~LlvmModelLibrary() { - // do not call clean-up here - // cleanUp() must be called by the subclass (before destruction of the execution engine...) - } - -protected: - inline LlvmModelLibrary() { - } - - inline void cleanUp() { - for (LlvmModel* model : _models) { - model->modelLibraryClosed(); - } - - if(this->_onClose != nullptr) { - (*this->_onClose)(); - this->_onClose = nullptr; - } - } - - virtual void destroyed(LlvmModel* model) { - _models.erase(model); - } - - friend class LlvmModel; -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_2/llvm3_2.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/v3_2/llvm3_2.hpp deleted file mode 100644 index 3a15cb2c5..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_2/llvm3_2.hpp +++ /dev/null @@ -1,90 +0,0 @@ -#ifndef CPPAD_CG_LLVM3_2_INCLUDED -#define CPPAD_CG_LLVM3_2_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -/** - * LLVM requires the use of it own flags which can make it difficult to compile - * libraries not using NDEBUG often required by LLVM. - * The define LLVM_CPPFLAG_NDEBUG can be used to apply NDEBUG only to LLVM - * headers. - */ -#ifdef LLVM_WITH_NDEBUG - -// save the original NDEBUG definition -#ifdef NDEBUG -#define _OUTER_NDEBUG_DEFINED -#endif - -#if LLVM_WITH_NDEBUG == 1 -#define NDEBUG -#else -#undef NDEBUG -#endif - -#endif - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#ifdef LLVM_WITH_NDEBUG - -// recover the original NDEBUG -#ifdef _OUTER_NDEBUG_DEFINED -#define NDEBUG -#else -#undef NDEBUG -#endif - -// no need for this anymore -#undef _OUTER_NDEBUG_DEFINED - -#endif - -#include -#include -#include -#include - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_2/llvm_model_library_3_2.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/v3_2/llvm_model_library_3_2.hpp deleted file mode 100644 index c0a71fdf7..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_2/llvm_model_library_3_2.hpp +++ /dev/null @@ -1,125 +0,0 @@ -#ifndef CPPAD_CG_LLVM_MODEL_LIBRARY_3_2_INCLUDED -#define CPPAD_CG_LLVM_MODEL_LIBRARY_3_2_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template class LlvmModel; - -/** - * Class used to load JIT'ed models by LLVM 3.2 - * - * @author Joao Leal - */ -template -class LlvmModelLibrary3_2 : public LlvmModelLibrary { -protected: - llvm::Module* _module; - std::unique_ptr _context; - std::unique_ptr _executionEngine; - std::unique_ptr _fpm; -public: - - LlvmModelLibrary3_2(llvm::Module* module, - llvm::LLVMContext* context) : - _module(module), - _context(context) { - using namespace llvm; - - // Create the JIT. This takes ownership of the module. - std::string errStr; - _executionEngine.reset(EngineBuilder(_module) - .setErrorStr(&errStr) - .setEngineKind(EngineKind::JIT) - .create()); - if (!_executionEngine.get()) { - throw CGException("Could not create ExecutionEngine: ", errStr); - } - - _fpm.reset(new llvm::FunctionPassManager(_module)); - - preparePassManager(); - - _fpm->doInitialization(); - - /** - * - */ - this->validate(); - } - - LlvmModelLibrary3_2(const LlvmModelLibrary3_2&) = delete; - LlvmModelLibrary3_2& operator=(const LlvmModelLibrary3_2&) = delete; - - inline virtual ~LlvmModelLibrary3_2() { - this->cleanUp(); - } - - /** - * Set up the optimizer pipeline - */ - virtual void preparePassManager() { - llvm::PassManagerBuilder builder; - builder.OptLevel = 2; - builder.populateFunctionPassManager(*_fpm); - - /* - // Set up the optimizer pipeline. Start with registering info about how the - // target lays out data structures. - _fpm->add(new DataLayout(*_executionEngine->getDataLayout())); - // Provide basic AliasAnalysis support for GVN. - _fpm->add(createBasicAliasAnalysisPass()); - // Do simple "peephole" optimizations and bit-twiddling optzns. - _fpm->add(createInstructionCombiningPass()); - // Re-associate expressions. - _fpm->add(createReassociatePass()); - // Eliminate Common SubExpressions. - _fpm->add(createGVNPass()); - _fpm->add(llvm::createDeadStoreEliminationPass()); // Delete dead stores - // Simplify the control flow graph (deleting unreachable blocks, etc). - _fpm->add(createCFGSimplificationPass()); - */ - } - - virtual void* loadFunction(const std::string& functionName, bool required = true) override { - llvm::Function* func = _module->getFunction(functionName); - if (func == nullptr) { - if (required) - throw CGException("Unable to find function '", functionName, "' in LLVM module"); - return nullptr; - } - -#ifndef NDEBUG - // Validate the generated code, checking for consistency. - llvm::verifyFunction(*func); -#endif - // Optimize the function. - _fpm->run(*func); - - // JIT the function, returning a function pointer. - void *fPtr = _executionEngine->getPointerToFunction(func); - return fPtr; - } - - friend class LlvmModel; - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_2/llvm_model_library_processor.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/v3_2/llvm_model_library_processor.hpp deleted file mode 100644 index 143409032..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_2/llvm_model_library_processor.hpp +++ /dev/null @@ -1,191 +0,0 @@ -#ifndef CPPAD_CG_LLVM_MODEL_LIBRARY_PROCESSOR_INCLUDED -#define CPPAD_CG_LLVM_MODEL_LIBRARY_PROCESSOR_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include - -namespace CppAD { -namespace cg { - -/** - * Useful class for generating a JIT evaluated model library. - * - * @author Joao Leal - */ -template -class LlvmModelLibraryProcessor : public LlvmBaseModelLibraryProcessor { -protected: - std::vector _includePaths; - std::unique_ptr _linker; - std::unique_ptr _context; -public: - - /** - * - * @param modelLibraryHelper - */ - LlvmModelLibraryProcessor(ModelLibraryCSourceGen& modelLibraryHelper) : - LlvmBaseModelLibraryProcessor(modelLibraryHelper) { - } - - virtual ~LlvmModelLibraryProcessor() { - } - - inline void setIncludePaths(const std::vector& includePaths) { - _includePaths = includePaths; - } - - inline const std::vector& getIncludePaths() const { - return _includePaths; - } - - LlvmModelLibrary* create() { - // backup output format so that it can be restored - OStreamConfigRestore coutb(std::cout); - - _linker.release(); - - this->modelLibraryHelper_->startingJob("", JobTimer::JIT_MODEL_LIBRARY); - - llvm::InitializeAllTargets(); - llvm::InitializeAllAsmPrinters(); - - _context.reset(new llvm::LLVMContext()); - - const std::map*>& models = this->modelLibraryHelper_->getModels(); - for (const auto& p : models) { - const std::map& modelSources = this->getSources(*p.second); - createLlvmModules(modelSources); - } - - const std::map& sources = this->getLibrarySources(); - createLlvmModules(sources); - - const std::map& customSource = this->modelLibraryHelper_->getCustomSources(); - createLlvmModules(customSource); - - llvm::InitializeNativeTarget(); - - LlvmModelLibrary3_2* lib = new LlvmModelLibrary3_2(_linker->releaseModule(), _context.release()); - - this->modelLibraryHelper_->finishedJob(); - - return lib; - } - - static inline LlvmModelLibrary* create(ModelLibraryCSourceGen& modelLibraryHelper) { - LlvmModelLibraryProcessor p(modelLibraryHelper); - return p.create(); - } - -protected: - - virtual void createLlvmModules(const std::map& sources) { - for (const auto& p : sources) { - createLlvmModule(p.first, p.second); - } - } - - virtual void createLlvmModule(const std::string& filename, - const std::string& source) { - using namespace llvm; - using namespace clang; - - static const char* argv [] = {"program", "-Wall", "-x", "c", "string-input"}; - static const int argc = sizeof (argv) / sizeof (argv[0]); - - IntrusiveRefCntPtr diagOpts = new DiagnosticOptions(); - TextDiagnosticPrinter *diagClient = new TextDiagnosticPrinter(llvm::errs(), &*diagOpts); // will be owned by diags - IntrusiveRefCntPtr diagID(new DiagnosticIDs()); - IntrusiveRefCntPtr diags(new DiagnosticsEngine(diagID, &*diagOpts, diagClient)); - - ArrayRef args(argv + 1, // skip program name - argc - 1); - std::unique_ptr invocation(createInvocationFromCommandLine(args, diags)); - if (invocation.get() == nullptr) - throw CGException("Failed to create compiler invocation"); - CompilerInvocation::setLangDefaults(*invocation->getLangOpts(), IK_C, - LangStandard::lang_unspecified); - invocation->getFrontendOpts().DisableFree = false; // make sure we free memory (by default it does not) - - // Create a compiler instance to handle the actual work. - CompilerInstance compiler; - compiler.setInvocation(invocation.release()); - - // Create the compilers actual diagnostics engine. - compiler.createDiagnostics(argc, const_cast (argv)); - if (!compiler.hasDiagnostics()) - throw CGException("No diagnostics"); - - // Create memory buffer with source text - llvm::MemoryBuffer * buffer = llvm::MemoryBuffer::getMemBufferCopy(source, "SIMPLE_BUFFER"); - if (buffer == nullptr) - throw CGException("Failed to create memory buffer"); - - // Remap auxiliary name "string-input" to memory buffer - PreprocessorOptions& po = compiler.getInvocation().getPreprocessorOpts(); - po.addRemappedFile("string-input", buffer); - - HeaderSearchOptions& hso = compiler.getInvocation().getHeaderSearchOpts(); - for (size_t s = 0; s < _includePaths.size(); s++) - hso.AddPath(llvm::StringRef(_includePaths[s]), clang::frontend::Angled, true, false, false); - - // Create and execute the frontend to generate an LLVM bitcode module. - OwningPtr action(new clang::EmitLLVMOnlyAction(_context.get())); - if (!compiler.ExecuteAction(*action)) - throw CGException("Failed to emit LLVM bitcode"); - - llvm::Module* module = action->takeModule(); - if (module == nullptr) - throw CGException("No module"); - - if (_linker.get() == nullptr) { - _linker.reset(new llvm::Linker(std::string("MyLinker"), module)); - } else { - std::string errorMsg; - if (_linker->LinkInModule(module, &errorMsg)) { - throw CGException(errorMsg); - } - } - - // NO delete module; - // NO delete invocation; - //llvm::llvm_shutdown(); - } - - inline llvm::Module* mergeModules(const std::vector& modules) { - if (modules.empty()) - return nullptr; - - std::string progName("MyLinker"); - std::unique_ptr ld(new llvm::Linker(progName, modules[0])); - - for (size_t m = 1; m < modules.size(); m++) { - std::string errorMsg; - if (ld->LinkInModule(modules[m], &errorMsg)) { - throw CGException(errorMsg); - } - } - - return ld->releaseModule(); - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_4/llvm3_4.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/v3_4/llvm3_4.hpp deleted file mode 100644 index cbe665539..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_4/llvm3_4.hpp +++ /dev/null @@ -1,76 +0,0 @@ -#ifndef CPPAD_CG_LLVM3_4_INCLUDED -#define CPPAD_CG_LLVM3_4_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -/** - * LLVM requires the use of it own flags which can make it difficult to compile - * libraries not using NDEBUG often required by LLVM. - * The define LLVM_CPPFLAG_NDEBUG can be used to apply NDEBUG only to LLVM - * headers. - */ -#ifdef LLVM_WITH_NDEBUG - -// save the original NDEBUG definition -#ifdef NDEBUG -#define _OUTER_NDEBUG_DEFINED -#endif - -#if LLVM_WITH_NDEBUG == 1 -#define NDEBUG -#else -#undef NDEBUG -#endif - -#endif - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#ifdef LLVM_WITH_NDEBUG - -// recover the original NDEBUG -#ifdef _OUTER_NDEBUG_DEFINED -#define NDEBUG -#else -#undef NDEBUG -#endif - -// no need for this anymore -#undef _OUTER_NDEBUG_DEFINED - -#endif - -#include -#include -#include -#include -#include - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_4/llvm_model_library_3_4.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/v3_4/llvm_model_library_3_4.hpp deleted file mode 100644 index e851e2ddc..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_4/llvm_model_library_3_4.hpp +++ /dev/null @@ -1,125 +0,0 @@ -#ifndef CPPAD_CG_LLVM_MODEL_LIBRARY_3_4_INCLUDED -#define CPPAD_CG_LLVM_MODEL_LIBRARY_3_4_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template class LlvmModel; - -/** - * Class used to load JIT'ed models by LLVM 3.4 - * - * @author Joao Leal - */ -template -class LlvmModelLibrary3_4 : public LlvmModelLibrary { -protected: - llvm::Module* _module; - std::unique_ptr _context; - std::unique_ptr _executionEngine; - std::unique_ptr _fpm; -public: - - LlvmModelLibrary3_4(llvm::Module* module, - llvm::LLVMContext* context) : - _module(module), - _context(context) { - using namespace llvm; - - // Create the JIT. This takes ownership of the module. - std::string errStr; - _executionEngine.reset(EngineBuilder(_module) - .setErrorStr(&errStr) - .setEngineKind(EngineKind::JIT) - .create()); - if (!_executionEngine.get()) { - throw CGException("Could not create ExecutionEngine: ", errStr); - } - - _fpm.reset(new llvm::FunctionPassManager(_module)); - - preparePassManager(); - - _fpm->doInitialization(); - - /** - * - */ - this->validate(); - } - - LlvmModelLibrary3_4(const LlvmModelLibrary3_4&) = delete; - LlvmModelLibrary3_4& operator=(const LlvmModelLibrary3_4&) = delete; - - inline virtual ~LlvmModelLibrary3_4() { - this->cleanUp(); - } - - /** - * Set up the optimizer pipeline - */ - virtual void preparePassManager() { - llvm::PassManagerBuilder builder; - builder.OptLevel = 2; - builder.populateFunctionPassManager(*_fpm); - - /* - // Set up the optimizer pipeline. Start with registering info about how the - // target lays out data structures. - _fpm->add(new DataLayout(*_executionEngine->getDataLayout())); - // Provide basic AliasAnalysis support for GVN. - _fpm->add(createBasicAliasAnalysisPass()); - // Do simple "peephole" optimizations and bit-twiddling optzns. - _fpm->add(createInstructionCombiningPass()); - // Re-associate expressions. - _fpm->add(createReassociatePass()); - // Eliminate Common SubExpressions. - _fpm->add(createGVNPass()); - _fpm->add(llvm::createDeadStoreEliminationPass()); // Delete dead stores - // Simplify the control flow graph (deleting unreachable blocks, etc). - _fpm->add(createCFGSimplificationPass()); - */ - } - - virtual void* loadFunction(const std::string& functionName, bool required = true) override { - llvm::Function* func = _module->getFunction(functionName); - if (func == nullptr) { - if (required) - throw CGException("Unable to find function '", functionName, "' in LLVM module"); - return nullptr; - } - -#ifndef NDEBUG - // Validate the generated code, checking for consistency. - llvm::verifyFunction(*func); -#endif - // Optimize the function. - _fpm->run(*func); - - // JIT the function, returning a function pointer. - void *fPtr = _executionEngine->getPointerToFunction(func); - return fPtr; - } - - friend class LlvmModel; - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_4/llvm_model_library_processor.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/v3_4/llvm_model_library_processor.hpp deleted file mode 100644 index 8810eb56b..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_4/llvm_model_library_processor.hpp +++ /dev/null @@ -1,210 +0,0 @@ -#ifndef CPPAD_CG_LLVM_MODEL_LIBRARY_PROCESSOR_INCLUDED -#define CPPAD_CG_LLVM_MODEL_LIBRARY_PROCESSOR_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include - -namespace CppAD { -namespace cg { - -/** - * Useful class for generating a JIT evaluated model library. - * - * @author Joao Leal - */ -template -class LlvmModelLibraryProcessor : public LlvmBaseModelLibraryProcessor { -protected: - std::vector _includePaths; - std::unique_ptr _linker; - std::unique_ptr _context; -public: - - /** - * - * @param modelLibraryHelper - */ - LlvmModelLibraryProcessor(ModelLibraryCSourceGen& modelLibraryHelper) : - LlvmBaseModelLibraryProcessor(modelLibraryHelper) { - } - - virtual ~LlvmModelLibraryProcessor() { - } - - inline void setIncludePaths(const std::vector& includePaths) { - _includePaths = includePaths; - } - - inline const std::vector& getIncludePaths() const { - return _includePaths; - } - - LlvmModelLibrary* create() { - ClangCompiler clang; - return create(clang); - } - - LlvmModelLibrary* create(ClangCompiler& clang) { - using namespace llvm; - - // backup output format so that it can be restored - OStreamConfigRestore coutb(std::cout); - - _linker.release(); - - LlvmModelLibrary3_4* lib = nullptr; - - this->modelLibraryHelper_->startingJob("", JobTimer::JIT_MODEL_LIBRARY); - - try { - /** - * generate bit code - */ - const std::set& bcFiles = this->createBitCode(clang, "3.4"); - - /** - * Load bit code and create a single module - */ - llvm::InitializeAllTargets(); - llvm::InitializeAllAsmPrinters(); - - _context.reset(new llvm::LLVMContext()); - - for (const std::string& itbc : bcFiles) { - // load bitcode file - OwningPtr buffer; - - error_code ec = MemoryBuffer::getFile(itbc, buffer); - if (buffer.get() == nullptr) - throw CGException(ec.message()); - - // create the module - std::string errMsg; - Module* module = llvm::ParseBitcodeFile(buffer.get(), *_context.get(), &errMsg); - if(module == nullptr) - throw CGException("Failed to create LLVM bitcode: ", errMsg); - - // link modules together - if (_linker.get() == nullptr) { - _linker.reset(new llvm::Linker(module)); // module not destroyed - } else { - if (_linker->linkInModule(module, &errMsg)) { // module destroyed - throw CGException(errMsg); - } - } - } - - llvm::InitializeNativeTarget(); - - // voila - lib = new LlvmModelLibrary3_4(_linker->getModule(), _context.release()); - - } catch (...) { - clang.cleanup(); - throw; - } - clang.cleanup(); - - this->modelLibraryHelper_->finishedJob(); - - return lib; - } - - static inline LlvmModelLibrary* create(ModelLibraryCSourceGen& modelLibraryHelper) { - LlvmModelLibraryProcessor p(modelLibraryHelper); - return p.create(); - } - -protected: -#if 0 - - /** - * Creates LLVM modules in a separate process. - */ - static void createnPrintModule() { - using namespace llvm; - using namespace clang; - - /** - * load source file - */ - std::string source; - std::cin >> source; - - static const char* argv [] = {"program", "-Wall", "-x", "c", "string-input"}; - static const int argc = sizeof (argv) / sizeof (argv[0]); - - IntrusiveRefCntPtr diagOpts = new DiagnosticOptions(); - TextDiagnosticPrinter *diagClient = new TextDiagnosticPrinter(llvm::errs(), &*diagOpts); // will be owned by diags - IntrusiveRefCntPtr diagID(new DiagnosticIDs()); - IntrusiveRefCntPtr diags(new DiagnosticsEngine(diagID, &*diagOpts, diagClient)); - - ArrayRef args(argv + 1, // skip program name - argc - 1); - std::unique_ptr invocation(createInvocationFromCommandLine(args, diags)); - if (invocation.get() == nullptr) - throw CGException("Failed to create compiler invocation"); - CompilerInvocation::setLangDefaults(*invocation->getLangOpts(), IK_C, - LangStandard::lang_unspecified); - invocation->getFrontendOpts().DisableFree = false; // make sure we free memory (by default it does not) - - // Create a compiler instance to handle the actual work. - CompilerInstance compiler; - compiler.setInvocation(invocation.release()); - - // Create the compilers actual diagnostics engine. - compiler.createDiagnostics(); - if (!compiler.hasDiagnostics()) - throw CGException("No diagnostics"); - - // Create memory buffer with source text - llvm::MemoryBuffer * buffer = llvm::MemoryBuffer::getMemBufferCopy(source, "SIMPLE_BUFFER"); - if (buffer == nullptr) - throw CGException("Failed to create memory buffer"); - - // Remap auxiliary name "string-input" to memory buffer - PreprocessorOptions& po = compiler.getInvocation().getPreprocessorOpts(); - po.addRemappedFile("string-input", buffer); - - HeaderSearchOptions& hso = compiler.getInvocation().getHeaderSearchOpts(); - for (size_t s = 0; s < _includePaths.size(); s++) - hso.AddPath(llvm::StringRef(_includePaths[s]), clang::frontend::Angled, true, false); - - // Create and execute the frontend to generate an LLVM bitcode module. - OwningPtr action(new clang::EmitLLVMOnlyAction(_context.get())); - - if (!compiler.ExecuteAction(*action)) - throw CGException("Failed to emit LLVM bitcode"); - - llvm::Module* module = action->takeModule(); - if (module == nullptr) - throw CGException("No module"); - - /** - * Print out the IR - */ - //std::cout << *module; - raw_fd_ostream os(STDOUT_FILENO, true); - module->print(os); - delete module; - } -#endif -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_6/llvm3_6.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/v3_6/llvm3_6.hpp deleted file mode 100644 index a36d4a59e..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_6/llvm3_6.hpp +++ /dev/null @@ -1,90 +0,0 @@ -#ifndef CPPAD_CG_LLVM3_6_INCLUDED -#define CPPAD_CG_LLVM3_6_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2015 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -/** - * LLVM requires the use of it own flags which can make it difficult to compile - * libraries not using NDEBUG often required by LLVM. - * The define LLVM_CPPFLAG_NDEBUG can be used to apply NDEBUG only to LLVM - * headers. - */ -#ifdef LLVM_WITH_NDEBUG - -// save the original NDEBUG definition -#ifdef NDEBUG -#define _OUTER_NDEBUG_DEFINED -#endif - -#if LLVM_WITH_NDEBUG == 1 -#define NDEBUG -#else -#undef NDEBUG -#endif - -#endif - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -//#include // force static initialisation -//#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -//#include -#include - -#ifdef LLVM_WITH_NDEBUG - -// recover the original NDEBUG -#ifdef _OUTER_NDEBUG_DEFINED -#define NDEBUG -#else -#undef NDEBUG -#endif - -// no need for this anymore -#undef _OUTER_NDEBUG_DEFINED - -#endif - -#include -#include -#include -#include -#include - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_6/llvm_model_library_3_6.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/v3_6/llvm_model_library_3_6.hpp deleted file mode 100644 index 6360772cd..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_6/llvm_model_library_3_6.hpp +++ /dev/null @@ -1,121 +0,0 @@ -#ifndef CPPAD_CG_LLVM_MODEL_LIBRARY_3_6_INCLUDED -#define CPPAD_CG_LLVM_MODEL_LIBRARY_3_6_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2015 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template class LlvmModel; - -/** - * Class used to load JIT'ed models by LLVM 3.6 - * - * @author Joao Leal - */ -template -class LlvmModelLibrary3_6 : public LlvmModelLibrary { -protected: - llvm::Module* _module; // owned by _executionEngine - std::unique_ptr _context; - std::unique_ptr _executionEngine; - std::unique_ptr _fpm; -public: - - LlvmModelLibrary3_6(llvm::Module* module, - llvm::LLVMContext* context) : - _module(module), - _context(context) { - using namespace llvm; - - // Create the JIT. This takes ownership of the module. - std::unique_ptr m(_module); - std::string errStr; - _executionEngine.reset(EngineBuilder(std::move(m)) - .setErrorStr(&errStr) - .setEngineKind(EngineKind::JIT) -#ifndef NDEBUG - .setVerifyModules(true) -#endif - // .setMCJITMemoryManager(llvm::make_unique()) - .create()); - if (!_executionEngine.get()) { - throw CGException("Could not create ExecutionEngine: ", errStr); - } - - _fpm.reset(new llvm::FunctionPassManager(_module)); - - preparePassManager(); - - _fpm->doInitialization(); - - /** - * - */ - this->validate(); - } - - LlvmModelLibrary3_6(const LlvmModelLibrary3_6&) = delete; - LlvmModelLibrary3_6& operator=(const LlvmModelLibrary3_6&) = delete; - - inline virtual ~LlvmModelLibrary3_6() { - this->cleanUp(); - } - - /** - * Set up the optimizer pipeline - */ - virtual void preparePassManager() { - llvm::PassManagerBuilder builder; - builder.OptLevel = 2; - builder.populateFunctionPassManager(*_fpm); - //_fpm.add(new DataLayoutPass()); - } - - virtual void* loadFunction(const std::string& functionName, bool required = true) override { - llvm::Function* func = _module->getFunction(functionName); - if (func == nullptr) { - if (required) - throw CGException("Unable to find function '", functionName, "' in LLVM module"); - return nullptr; - } - -#ifndef NDEBUG - // Validate the generated code, checking for consistency. - llvm::raw_os_ostream os(std::cerr); - bool failed = llvm::verifyFunction(*func, &os); - if (failed) - throw CGException("Function '", functionName, "' verification failed"); -#endif - - // Optimize the function. - _fpm->run(*func); - - // JIT the function, returning a function pointer. - uint64_t fPtr = _executionEngine->getFunctionAddress(functionName); - if (fPtr == 0 && required) { - throw CGException("Unable to find function '", functionName, "' in LLVM module"); - } - return (void*) fPtr; - } - - friend class LlvmModel; - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_6/llvm_model_library_processor.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/v3_6/llvm_model_library_processor.hpp deleted file mode 100644 index ce8dff525..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_6/llvm_model_library_processor.hpp +++ /dev/null @@ -1,190 +0,0 @@ -#ifndef CPPAD_CG_LLVM_MODEL_LIBRARY_PROCESSOR_INCLUDED -#define CPPAD_CG_LLVM_MODEL_LIBRARY_PROCESSOR_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2015 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include - -namespace CppAD { -namespace cg { - -/** - * Useful class for generating a JIT evaluated model library. - * - * @author Joao Leal - */ -template -class LlvmModelLibraryProcessor : public LlvmBaseModelLibraryProcessor { -protected: - std::vector _includePaths; - std::unique_ptr _linker; - std::unique_ptr _context; - std::unique_ptr _module; -public: - - /** - * - * @param modelLibraryHelper - */ - LlvmModelLibraryProcessor(ModelLibraryCSourceGen& modelLibraryHelper) : - LlvmBaseModelLibraryProcessor(modelLibraryHelper) { - } - - virtual ~LlvmModelLibraryProcessor() { - } - - inline void setIncludePaths(const std::vector& includePaths) { - _includePaths = includePaths; - } - - inline const std::vector& getIncludePaths() const { - return _includePaths; - } - - LlvmModelLibrary* create() { - // backup output format so that it can be restored - OStreamConfigRestore coutb(std::cout); - - _linker.reset(nullptr); - - this->modelLibraryHelper_->startingJob("", JobTimer::JIT_MODEL_LIBRARY); - - llvm::InitializeAllTargets(); - llvm::InitializeAllAsmPrinters(); - - _context.reset(new llvm::LLVMContext()); - - const std::map*>& models = this->modelLibraryHelper_->getModels(); - for (const auto& p : models) { - const std::map& modelSources = this->getSources(*p.second); - createLlvmModules(modelSources); - } - - const std::map& sources = this->getLibrarySources(); - createLlvmModules(sources); - - const std::map& customSource = this->modelLibraryHelper_->getCustomSources(); - createLlvmModules(customSource); - - llvm::InitializeNativeTarget(); - - LlvmModelLibrary3_6* lib = new LlvmModelLibrary3_6(_module.release(), _context.release()); - - this->modelLibraryHelper_->finishedJob(); - - return lib; - } - - static inline LlvmModelLibrary* create(ModelLibraryCSourceGen& modelLibraryHelper) { - LlvmModelLibraryProcessor p(modelLibraryHelper); - return p.create(); - } - -protected: - - virtual void createLlvmModules(const std::map& sources) { - for (const auto& p : sources) { - createLlvmModule(p.first, p.second); - } - } - - virtual void createLlvmModule(const std::string& filename, - const std::string& source) { - using namespace llvm; - using namespace clang; - - static const char* argv [] = {"program", "-Wall", "-x", "c", "string-input"}; // -Wall or -v flag is required to avoid an error inside createInvocationFromCommandLine() - static const int argc = sizeof (argv) / sizeof (argv[0]); - - IntrusiveRefCntPtr diagOpts = new DiagnosticOptions(); - TextDiagnosticPrinter* diagClient = new TextDiagnosticPrinter(llvm::errs(), &*diagOpts); // will be owned by diags - IntrusiveRefCntPtr diagID(new DiagnosticIDs()); - IntrusiveRefCntPtr diags(new DiagnosticsEngine(diagID, &*diagOpts, diagClient)); - - ArrayRef args(argv + 1, // skip program name - argc - 1); - std::unique_ptr invocation(createInvocationFromCommandLine(args, diags)); - if (invocation.get() == nullptr) - throw CGException("Failed to create compiler invocation"); - CompilerInvocation::setLangDefaults(*invocation->getLangOpts(), IK_C, - LangStandard::lang_unspecified); - invocation->getFrontendOpts().DisableFree = false; // make sure we free memory (by default it does not) - - // Create a compiler instance to handle the actual work. - CompilerInstance compiler; - compiler.setInvocation(invocation.release()); - - - // Create the compilers actual diagnostics engine. - compiler.createDiagnostics(); //compiler.createDiagnostics(argc, const_cast (argv)); - if (!compiler.hasDiagnostics()) - throw CGException("No diagnostics"); -#if 0 - compiler.createFileManager(); - compiler.createSourceManager(compiler.getFileManager()); - std::shared_ptr pto = std::make_shared(); - pto->Triple = llvm::sys::getDefaultTargetTriple(); - clang::TargetInfo *pti = clang::TargetInfo::CreateTargetInfo(compiler.getDiagnostics(), pto); - compiler.setTarget(pti); - compiler.createPreprocessor(clang::TU_Complete); -#endif - - // Create memory buffer with source text - std::unique_ptr buffer = llvm::MemoryBuffer::getMemBufferCopy(source, "SIMPLE_BUFFER"); - if (buffer.get() == nullptr) - throw CGException("Failed to create memory buffer"); - - // Remap auxiliary name "string-input" to memory buffer - PreprocessorOptions& po = compiler.getInvocation().getPreprocessorOpts(); - po.addRemappedFile("string-input", buffer.release()); - - HeaderSearchOptions& hso = compiler.getInvocation().getHeaderSearchOpts(); - std::string iClangHeaders = this->findInternalClangCHeaders("3.6", hso.ResourceDir); - if(!iClangHeaders.empty()) { - hso.AddPath(llvm::StringRef(iClangHeaders), clang::frontend::Angled, false, false); - } - - for (size_t s = 0; s < _includePaths.size(); s++) - hso.AddPath(llvm::StringRef(_includePaths[s]), clang::frontend::Angled, false, false); - - // Create and execute the frontend to generate an LLVM bitcode module. - clang::EmitLLVMOnlyAction action(_context.get()); - if (!compiler.ExecuteAction(action)) - throw CGException("Failed to emit LLVM bitcode"); - - std::unique_ptr module = action.takeModule(); - if (module.get() == nullptr) - throw CGException("No module"); - - if (_linker.get() == nullptr) { - _module.reset(module.release()); - _linker.reset(new llvm::Linker(_module.get())); - } else { - if (_linker->linkInModule(module.release())) { - throw CGException("LLVM failed to link module"); - } - } - - // NO delete module; - // NO delete invocation; - //llvm::llvm_shutdown(); - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_8/llvm3_8.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/v3_8/llvm3_8.hpp deleted file mode 100644 index 1c8fdcc28..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_8/llvm3_8.hpp +++ /dev/null @@ -1,90 +0,0 @@ -#ifndef CPPAD_CG_LLVM3_8_INCLUDED -#define CPPAD_CG_LLVM3_8_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -/** - * LLVM requires the use of it own flags which can make it difficult to compile - * libraries not using NDEBUG often required by LLVM. - * The define LLVM_CPPFLAG_NDEBUG can be used to apply NDEBUG only to LLVM - * headers. - */ -#ifdef LLVM_WITH_NDEBUG - -// save the original NDEBUG definition -#ifdef NDEBUG -#define _OUTER_NDEBUG_DEFINED -#endif - -#if LLVM_WITH_NDEBUG == 1 -#define NDEBUG -#else -#undef NDEBUG -#endif - -#endif - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -//#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -//#include -#include -#include - -#ifdef LLVM_WITH_NDEBUG - -// recover the original NDEBUG -#ifdef _OUTER_NDEBUG_DEFINED -#define NDEBUG -#else -#undef NDEBUG -#endif - -// no need for this anymore -#undef _OUTER_NDEBUG_DEFINED - -#endif - -#include -#include -#include -#include -#include - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_8/llvm_model_library_3_8.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/v3_8/llvm_model_library_3_8.hpp deleted file mode 100644 index 842fe07f5..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_8/llvm_model_library_3_8.hpp +++ /dev/null @@ -1,121 +0,0 @@ -#ifndef CPPAD_CG_LLVM_MODEL_LIBRARY_3_8_INCLUDED -#define CPPAD_CG_LLVM_MODEL_LIBRARY_3_8_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template class LlvmModel; - -/** - * Class used to load JIT'ed models by LLVM 3.8 - * - * @author Joao Leal - */ -template -class LlvmModelLibrary3_8 : public LlvmModelLibrary { -protected: - llvm::Module* _module; // owned by _executionEngine - std::unique_ptr _context; - std::unique_ptr _executionEngine; - std::unique_ptr _fpm; -public: - - LlvmModelLibrary3_8(llvm::Module* module, - llvm::LLVMContext* context) : - _module(module), - _context(context) { - using namespace llvm; - - // Create the JIT. This takes ownership of the module. - std::unique_ptr m(_module); - std::string errStr; - _executionEngine.reset(EngineBuilder(std::move(m)) - .setErrorStr(&errStr) - .setEngineKind(EngineKind::JIT) -#ifndef NDEBUG - .setVerifyModules(true) -#endif - // .setMCJITMemoryManager(llvm::make_unique()) - .create()); - if (!_executionEngine.get()) { - throw CGException("Could not create ExecutionEngine: ", errStr); - } - - _fpm.reset(new llvm::legacy::FunctionPassManager(_module)); - - preparePassManager(); - - _fpm->doInitialization(); - - /** - * - */ - this->validate(); - } - - LlvmModelLibrary3_8(const LlvmModelLibrary3_8&) = delete; - LlvmModelLibrary3_8& operator=(const LlvmModelLibrary3_8&) = delete; - - inline virtual ~LlvmModelLibrary3_8() { - this->cleanUp(); - } - - /** - * Set up the optimizer pipeline - */ - virtual void preparePassManager() { - llvm::PassManagerBuilder builder; - builder.OptLevel = 2; - builder.populateFunctionPassManager(*_fpm); - //_fpm.add(new DataLayoutPass()); - } - - virtual void* loadFunction(const std::string& functionName, bool required = true) override { - llvm::Function* func = _module->getFunction(functionName); - if (func == nullptr) { - if (required) - throw CGException("Unable to find function '", functionName, "' in LLVM module"); - return nullptr; - } - -#ifndef NDEBUG - // Validate the generated code, checking for consistency. - llvm::raw_os_ostream os(std::cerr); - bool failed = llvm::verifyFunction(*func, &os); - if (failed) - throw CGException("Function '", functionName, "' verification failed"); -#endif - - // Optimize the function. - _fpm->run(*func); - - // JIT the function, returning a function pointer. - uint64_t fPtr = _executionEngine->getFunctionAddress(functionName); - if (fPtr == 0 && required) { - throw CGException("Unable to find function '", functionName, "' in LLVM module"); - } - return (void*) fPtr; - } - - friend class LlvmModel; - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_8/llvm_model_library_processor.hpp b/ct_core/include/ct/external/cppad/cg/model/llvm/v3_8/llvm_model_library_processor.hpp deleted file mode 100644 index 8fc389a82..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/llvm/v3_8/llvm_model_library_processor.hpp +++ /dev/null @@ -1,282 +0,0 @@ -#ifndef CPPAD_CG_LLVM_MODEL_LIBRARY_PROCESSOR_INCLUDED -#define CPPAD_CG_LLVM_MODEL_LIBRARY_PROCESSOR_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include - -namespace CppAD { -namespace cg { - -/** - * Useful class for generating a JIT evaluated model library. - * - * @author Joao Leal - */ -template -class LlvmModelLibraryProcessor : public LlvmBaseModelLibraryProcessor { -protected: - std::vector _includePaths; - std::unique_ptr _linker; - std::unique_ptr _context; - std::unique_ptr _module; -public: - - /** - * - * @param modelLibraryHelper - */ - LlvmModelLibraryProcessor(ModelLibraryCSourceGen& modelLibraryHelper) : - LlvmBaseModelLibraryProcessor(modelLibraryHelper) { - } - - virtual ~LlvmModelLibraryProcessor() { - } - - inline void setIncludePaths(const std::vector& includePaths) { - _includePaths = includePaths; - } - - inline const std::vector& getIncludePaths() const { - return _includePaths; - } - - /** - * - * @return a model library - */ - LlvmModelLibrary* create() { -#if 0 - llvm::sys::Path clangPath = llvm::sys::Program::FindProgramByName("clang"); - // Arguments to pass to the clang driver: - // clang getinmemory.c -lcurl -v - vector args; - args.push_back(clangPath.c_str()); - args.push_back(inputPath.c_str()); - args.push_back("-l"); - args.push_back("curl"); - args.push_back("-v"); // verbose - - // The clang driver needs a DiagnosticsEngine so it can report problems - clang::TextDiagnosticPrinter *DiagClient = new clang::TextDiagnosticPrinter(llvm::errs(), clang::DiagnosticOptions()); - clang::IntrusiveRefCntPtr DiagID(new clang::DiagnosticIDs()); - clang::DiagnosticsEngine Diags(DiagID, DiagClient); - - // Create the clang driver - clang::driver::Driver TheDriver(args[0], llvm::sys::getDefaultTargetTriple(), outputPath, true, Diags); -#endif - // backup output format so that it can be restored - OStreamConfigRestore coutb(std::cout); - - _linker.reset(nullptr); - - this->modelLibraryHelper_->startingJob("", JobTimer::JIT_MODEL_LIBRARY); - - llvm::InitializeAllTargets(); - llvm::InitializeAllAsmPrinters(); - - _context.reset(new llvm::LLVMContext()); - - const std::map*>& models = this->modelLibraryHelper_->getModels(); - for (const auto& p : models) { - const std::map& modelSources = this->getSources(*p.second); - createLlvmModules(modelSources); - } - - const std::map& sources = this->getLibrarySources(); - createLlvmModules(sources); - - const std::map& customSource = this->modelLibraryHelper_->getCustomSources(); - createLlvmModules(customSource); - - llvm::InitializeNativeTarget(); - - LlvmModelLibrary3_8* lib = new LlvmModelLibrary3_8(_module.release(), _context.release()); - - this->modelLibraryHelper_->finishedJob(); - - return lib; - } - - /** - * - * @param clang the external compiler - * @return a model library - */ - LlvmModelLibrary* create(ClangCompiler& clang) { - using namespace llvm; - - // backup output format so that it can be restored - OStreamConfigRestore coutb(std::cout); - - _linker.release(); - - LlvmModelLibrary3_8* lib = nullptr; - - this->modelLibraryHelper_->startingJob("", JobTimer::JIT_MODEL_LIBRARY); - - const std::map*>& models = this->modelLibraryHelper_->getModels(); - try { - /** - * generate bit code - */ - const std::set& bcFiles = this->createBitCode(clang, "3.8"); - - /** - * Load bit code and create a single module - */ - llvm::InitializeAllTargets(); - llvm::InitializeAllAsmPrinters(); - - _context.reset(new llvm::LLVMContext()); - - std::unique_ptr linkerModule; - - for (const std::string& itbc : bcFiles) { - // load bitcode file - - ErrorOr> buffer = MemoryBuffer::getFile(itbc); - if (buffer.get() == nullptr) { - throw CGException(buffer.getError().message()); - } - - // create the module - ErrorOr> module = llvm::parseBitcodeFile(buffer.get()->getMemBufferRef(), *_context.get()); - if(module.get() == nullptr) { - throw CGException(module.getError().message()); - } - - // link modules together - if (_linker.get() == nullptr) { - linkerModule.reset(module.get().release()); - _linker.reset(new llvm::Linker(*linkerModule)); // module not destroyed - } else { - if (_linker->linkInModule(std::move(module.get()))) { // module destroyed - throw CGException("Failed to link"); - } - } - } - - llvm::InitializeNativeTarget(); - - // voila - lib = new LlvmModelLibrary3_8(linkerModule.release(), _context.release()); - - } catch (...) { - clang.cleanup(); - throw; - } - clang.cleanup(); - - this->modelLibraryHelper_->finishedJob(); - - return lib; - } - - static inline LlvmModelLibrary* create(ModelLibraryCSourceGen& modelLibraryHelper) { - LlvmModelLibraryProcessor p(modelLibraryHelper); - return p.create(); - } - -protected: - - virtual void createLlvmModules(const std::map& sources) { - for (const auto& p : sources) { - createLlvmModule(p.first, p.second); - } - } - - virtual void createLlvmModule(const std::string& filename, - const std::string& source) { - using namespace llvm; - using namespace clang; - - ArrayRef paths; - llvm::sys::findProgramByName("clang", paths); - - static const char* argv [] = {"program", "-Wall", "-x", "c", "string-input"}; // -Wall or -v flag is required to avoid an error inside createInvocationFromCommandLine() - static const int argc = sizeof (argv) / sizeof (argv[0]); - - IntrusiveRefCntPtr diagOpts = new DiagnosticOptions(); - TextDiagnosticPrinter* diagClient = new TextDiagnosticPrinter(llvm::errs(), &*diagOpts); // will be owned by diags - IntrusiveRefCntPtr diagID(new DiagnosticIDs()); - IntrusiveRefCntPtr diags(new DiagnosticsEngine(diagID, &*diagOpts, diagClient)); - - ArrayRef args(argv + 1, // skip program name - argc - 1); - std::unique_ptr invocation(createInvocationFromCommandLine(args, diags)); - if (invocation.get() == nullptr) - throw CGException("Failed to create compiler invocation"); - CompilerInvocation::setLangDefaults(*invocation->getLangOpts(), IK_C, - LangStandard::lang_unspecified); - invocation->getFrontendOpts().DisableFree = false; // make sure we free memory (by default it does not) - - // Create a compiler instance to handle the actual work. - CompilerInstance compiler; - compiler.setInvocation(invocation.release()); - - - // Create the compilers actual diagnostics engine. - compiler.createDiagnostics(); //compiler.createDiagnostics(argc, const_cast (argv)); - if (!compiler.hasDiagnostics()) - throw CGException("No diagnostics"); - - // Create memory buffer with source text - std::unique_ptr buffer = llvm::MemoryBuffer::getMemBufferCopy(source, "SIMPLE_BUFFER"); - if (buffer.get() == nullptr) - throw CGException("Failed to create memory buffer"); - - // Remap auxiliary name "string-input" to memory buffer - PreprocessorOptions& po = compiler.getInvocation().getPreprocessorOpts(); - po.addRemappedFile("string-input", buffer.release()); - - HeaderSearchOptions& hso = compiler.getInvocation().getHeaderSearchOpts(); - std::string iClangHeaders = this->findInternalClangCHeaders("3.8", hso.ResourceDir); - if(!iClangHeaders.empty()) { - hso.AddPath(llvm::StringRef(iClangHeaders), clang::frontend::Angled, false, false); - } - - for (size_t s = 0; s < _includePaths.size(); s++) - hso.AddPath(llvm::StringRef(_includePaths[s]), clang::frontend::Angled, false, false); - - // Create and execute the frontend to generate an LLVM bitcode module. - clang::EmitLLVMOnlyAction action(_context.get()); - if (!compiler.ExecuteAction(action)) - throw CGException("Failed to emit LLVM bitcode"); - - std::unique_ptr module = action.takeModule(); - if (module.get() == nullptr) - throw CGException("No module"); - - if (_linker.get() == nullptr) { - _module.reset(module.release()); - _linker.reset(new llvm::Linker(*_module.get())); - } else { - if (_linker->linkInModule(std::move(module))) { - throw CGException("LLVM failed to link module"); - } - } - - // NO delete module; - // NO delete invocation; - //llvm::llvm_shutdown(); - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen.hpp b/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen.hpp deleted file mode 100644 index 6858d8ba5..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen.hpp +++ /dev/null @@ -1,1236 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Auxiliary internal class - */ -class CompressedVectorInfo { -public: - std::vector > locations; // location of each index in the compressed array - std::vector indexes; // row or column index - bool ordered; -}; - -/** - * Generates C source code for a model. - * - * @author Joao Leal - */ -template -class ModelCSourceGen { - typedef CppAD::cg::CG CGBase; - typedef CppAD::AD ADCG; - typedef std::vector > SparsitySetType; - typedef std::pair TapeVarType; // tape independent -> reference orig independent (temporaries only) -public: - static const std::string FUNCTION_FORWAD_ZERO; - static const std::string FUNCTION_JACOBIAN; - static const std::string FUNCTION_HESSIAN; - static const std::string FUNCTION_FORWARD_ONE; - static const std::string FUNCTION_REVERSE_ONE; - static const std::string FUNCTION_REVERSE_TWO; - static const std::string FUNCTION_SPARSE_JACOBIAN; - static const std::string FUNCTION_SPARSE_HESSIAN; - static const std::string FUNCTION_JACOBIAN_SPARSITY; - static const std::string FUNCTION_HESSIAN_SPARSITY; - static const std::string FUNCTION_HESSIAN_SPARSITY2; - static const std::string FUNCTION_SPARSE_FORWARD_ONE; - static const std::string FUNCTION_SPARSE_REVERSE_ONE; - static const std::string FUNCTION_SPARSE_REVERSE_TWO; - static const std::string FUNCTION_FORWARD_ONE_SPARSITY; - static const std::string FUNCTION_REVERSE_ONE_SPARSITY; - static const std::string FUNCTION_REVERSE_TWO_SPARSITY; - static const std::string FUNCTION_INFO; - static const std::string FUNCTION_ATOMIC_FUNC_NAMES; -protected: - static const std::string CONST; - - /** - * Useful class for storing matrix indexes - */ - class Position { - public: - bool defined; - std::vector row; - std::vector col; - - inline Position() : - defined(false) { - } - - inline Position(const std::vector& r, const std::vector& c) : - defined(true), - row(r), - col(c) { - CPPADCG_ASSERT_KNOWN(r.size() == c.size(), "The number of row indexes must be the same as the number of column indexes."); - } - - template - inline Position(const VectorSet& elements) : - defined(true) { - size_t nnz = 0; - for (size_t i = 0; i < elements.size(); i++) { - nnz += elements[i].size(); - } - row.resize(nnz); - col.resize(nnz); - - nnz = 0; - for (size_t i = 0; i < elements.size(); i++) { - for (size_t it : elements[i]) { - row[nnz] = i; - col[nnz] = it; - nnz++; - } - } - } - }; - - /** - * Saves sparsity information in more than one format - */ - class LocalSparsityInfo { - public: - /** - * Calculated sparsity from the model - * (may differ from the requested sparsity) - */ - SparsitySetType sparsity; - // rows (in a custom order) - std::vector rows; - // columns (in a custom order) - std::vector cols; - }; - - /** - * Used for coloring - */ - class Color { - public: - /// all row with this color - std::set rows; - /// maps column indexes to the corresponding row - std::map column2Row; - /// maps row indexes to the corresponding columns - std::map > row2Columns; - /// used columns - std::set forbiddenRows; - }; - -protected: - /** - * the original model - */ - ADFun& _fun; - /** - * Altered model without the loop equations and with extra dependents - * for the non-indexed temporary variables used by loops - */ - LoopFreeModel* _funNoLoops; - /** - * loop models - */ - std::set*> _loopTapes; - /** - * the name of the model - */ - std::string _name; - /** - * the name of the data type used in operations - */ - const std::string _baseTypeName; - /** - * the maximum precision used to print values - */ - size_t _parameterPrecision; - /** - * Typical values of the independent vector - */ - std::vector _x; - /** - * Whether or not to enable the generation of multithreaded code for the - * sparse Jacobian and sparse Hessian if possible and requested by the - * model library (experimental). - */ - bool _multiThreading; - /// generate source code for the zero order model evaluation - bool _zero; - bool _zeroEvaluated; - /// generate source code for a dense Jacobian - bool _jacobian; - /// generate source code for a dense Hessian - bool _hessian; - /// generate source code for a sparse Jacobian - bool _sparseJacobian; - /// generate source code for a sparse Hessian - bool _sparseHessian; - /** - * generate source-code for the Hessian sparsity pattern for each - * equation/dependent - */ - bool _hessianByEquation; - /// generate source code for forward first order mode - bool _forwardOne; - /// generate source code for reverse first order mode - bool _reverseOne; - /// generate source code for reverse second order mode - bool _reverseTwo; - /** - * whether or not the sparse Jacobian should reuse the forward or reverse - * one functions when _sparseJacobian is true - */ - bool _sparseJacobianReusesOne; - /** - * whether or not the sparse Hessian should reuse the reverse two - * functions when _sparseHessian is true - */ - bool _sparseHessianReusesRev2; - JacobianADMode _jacMode; - /** - * Custom Jacobian element indexes - */ - Position _custom_jac; - LocalSparsityInfo _jacSparsity; - /** - * Custom Hessian element indexes - */ - Position _custom_hess; - LocalSparsityInfo _hessSparsity; - /** - * Hessian sparsity from the model for each equation - */ - std::vector _hessSparsities; - /** - * The order of the atomic functions - */ - std::vector _atomicFunctions; - /** - * Maps each atomic function ID to the independent variable indexes - * which affect a call of that atomic function - */ - std::map >* _atomicsIndeps; - /** - * A string cache for code generation - */ - std::ostringstream _cache; - /** - * maximum number of assignments per function (~ lines) - */ - size_t _maxAssignPerFunc; - /** - * - */ - std::vector > _relatedDepCandidates; - /** - * Maps the column groups of each loop model to the set of columns - * (loop->group->{columns->{compressed forward 1 position} }) - */ - std::map*, std::map > > > _loopFor1Groups; - /** - * Jacobian columns with a contribution from non loop equations - * [var]{compressed forward 1 position} - */ - std::map > _nonLoopFor1Elements; - /** - * Maps the column groups of each loop model to the set of columns - * (loop->group->{row->{compressed reverse 1 position} }) - */ - std::map*, std::map > > > _loopRev1Groups; - /** - * Jacobian rows with a contribution from non loop equations - * [eq]{compressed reverse 1 position} - */ - std::map > _nonLoopRev1Elements; - /** - * Maps the row groups of each loop model to the set of rows - * (loop->group->{rows->{compressed reverse 2 position} }) - */ - std::map*, std::map > > > _loopRev2Groups; - /** - * Hessian rows with a contribution from non loop equations - * [var]{compressed reverse 2 position} - */ - std::map > _nonLoopRev2Elements; - /** - * - */ - JobTimer* _jobTimer; - /** - * Generated source code (maps file names to content) - */ - std::map _sources; -public: - - /** - * Creates a new C language compilation helper for a model - * - * @param fun The ADFun with the taped model (should only be deleted - * after this object) - * @param model The model name (must be a valid C function name) - */ - ModelCSourceGen(ADFun >& fun, - const std::string& model) : - _fun(fun), - _funNoLoops(nullptr), - _name(model), - _baseTypeName(ModelCSourceGen::baseTypeName()), - _parameterPrecision(std::numeric_limits::digits10), - _multiThreading(true), - _zero(true), - _zeroEvaluated(false), - _jacobian(false), - _hessian(false), - _sparseJacobian(false), - _sparseHessian(false), - _hessianByEquation(false), - _forwardOne(false), - _reverseOne(false), - _reverseTwo(false), - _sparseJacobianReusesOne(true), - _sparseHessianReusesRev2(true), - _jacMode(JacobianADMode::Automatic), - _atomicsIndeps(nullptr), - _maxAssignPerFunc(20000), - _jobTimer(nullptr) { - - CPPADCG_ASSERT_KNOWN(!_name.empty(), "Model name cannot be empty"); - CPPADCG_ASSERT_KNOWN((_name[0] >= 'a' && _name[0] <= 'z') || - (_name[0] >= 'A' && _name[0] <= 'Z'), - "Invalid model name character"); - for (size_t i = 1; i < _name.size(); i++) { - char c = _name[i]; - CPPADCG_ASSERT_KNOWN((c >= 'a' && c <= 'z') || - (c >= 'A' && c <= 'Z') || - (c >= '0' && c <= '9') || - c == '_' - , "Invalid model name character"); - } - } - - ModelCSourceGen(const ModelCSourceGen&) = delete; - ModelCSourceGen& operator=(const ModelCSourceGen&) = delete; - - /** - * Provides the model name which should be a valid C function name. - * - * @return the model name - */ - inline const std::string& getName() const { - return _name; - } - - /** - * Defines typical values for the independent variable vector. These - * values can be useful when there is a need to call atomic functions, - * since they may allow to reduce some operations. - * - * @param x The typical values. An empty vector removes the currently - * defined values. - */ - template - inline void setTypicalIndependentValues(const VectorBase& x) { - CPPAD_ASSERT_KNOWN(x.size() == 0 || x.size() == _fun.Domain(), - "Invalid independent variable vector size"); - _x.resize(x.size()); - for (size_t i = 0; i < x.size(); i++) { - _x[i] = x[i]; - } - } - - inline void setRelatedDependents(const std::vector >& relatedDepCandidates) { - _relatedDepCandidates = relatedDepCandidates; - } - - inline const std::vector >& getRelatedDependents() const { - return _relatedDepCandidates; - } - - /** - * Provides the maximum precision used to print constant values in the - * generated source code - * - * @return the maximum number of digits - */ - virtual size_t getParameterPrecision() const { - return _parameterPrecision; - } - - /** - * Defines the maximum precision used to print constant values in the - * generated source code. - * - * @param p the maximum number of digits - */ - virtual void setParameterPrecision(size_t p) { - _parameterPrecision = p; - } - - /** - * Returns whether or not multithreading directives can be generated to - * parallelize the sparse Jacobian and sparse Hessian evaluation. - * Multithreaded code is only generated if requested by the model library. - * For the sparse Jacobian, the _sparseJacobianReusesOne must be enabled, - * at least one of _forwardOne and _reverseOne must be enabled, and loop - * detection must be disabled. - * For the sparse Hessian, the _sparseHessianReusesRev2 and _reverseTwo - * must be enabled and loop detection must be disabled. - * - * @return whether or not multithreading can be used for this model - */ - inline bool isMultiThreading() const { - return _multiThreading; - } - - /** - * Defines whether or not multithreading directives can be generated to - * parallelize the sparse Jacobian and sparse Hessian evaluation. - * Multithreaded code is only generated if requested by the model library. - * For the sparse Jacobian, the _sparseJacobianReusesOne must be enabled, - * at least one of _forwardOne and _reverseOne must be enabled, and loop - * detection must be disabled. - * For the sparse Hessian, the _sparseHessianReusesRev2 and _reverseTwo - * must be enabled and loop detection must be disabled. - * - * @param multiThreading whether or not multithreading can be used for this - * model - */ - inline void setMultiThreading(bool multiThreading) { - _multiThreading = multiThreading; - } - - inline bool isJacobianMultiThreadingEnabled() const { - return _multiThreading && _loopTapes.empty() && _sparseJacobian && _sparseJacobianReusesOne && (_forwardOne || _reverseOne); - } - - inline bool isHessianMultiThreadingEnabled() const { - return _multiThreading && _loopTapes.empty() && _sparseHessian && _sparseHessianReusesRev2 && _reverseTwo; - } - - /** - * Determines whether or not to generate source-code for a function - * that evaluates a dense Hessian. - * - * @return true if source-code for a dense Hessian should be created, - * false otherwise - */ - inline bool isCreateHessian() const { - return _hessian; - } - - /** - * Defines whether or not to generate source-code for a function - * that evaluates a dense Hessian. - * - * @param create true if source-code for a dense Hessian should be - * created, false otherwise - */ - inline void setCreateHessian(bool create) { - _hessian = create; - } - - /** - * Provides the Automatic Differentiation mode used to generate the - * source code for the Jacobian - * - * @return the Automatic Differentiation mode - */ - inline JacobianADMode getJacobianADMode() const { - return _jacMode; - } - - /** - * Defines the Automatic Differentiation mode used to generate the - * source code for the Jacobian - * - * @param mode the Automatic Differentiation mode - */ - inline void setJacobianADMode(JacobianADMode mode) { - _jacMode = mode; - } - - /** - * Determines whether or not to generate source-code for a function - * that evaluates a dense Jacobian. - * - * @return true if source-code for a dense Jacobian should be created, - * false otherwise - */ - inline bool isCreateJacobian() const { - return _jacobian; - } - - /** - * Defines whether or not to generate source-code for a function - * that evaluates a dense Jacobian. - * - * @param create true if source-code for a dense Jacobian should be - * created, false otherwise - */ - inline void setCreateJacobian(bool create) { - _jacobian = create; - } - - /** - * Determines whether or not to generate source-code for a function - * that evaluates a sparse Hessian. - * If ReverseTwo and SparseHessianReusesRev2 are also enabled the generated - * source-code will use the individual generated functions from the - * second-order reverse mode. - * Enabling the generation of individuals functions for reverse-mode - * can have a negative impact on the performance of the evaluation of the - * sparse hessian since Hessian symmetry will not be exploited. To - * improve performance one can request only the upper or lower elements - * of the hessian using setCustomSparseHessianElements(). - * - * @see setCustomSparseHessianElements() - * @see setSparseHessianReusesRev2() - * - * @return true if source-code for a sparse Hessian should be created, - * false otherwise - */ - inline bool isCreateSparseHessian() const { - return _sparseHessian; - } - - /** - * Defines whether or not to generate source-code for a function - * that evaluates a sparse Hessian. - * If ReverseTwo and SparseHessianReusesRev2 are also enabled the generated - * source-code will use the individual generated functions from the - * second-order reverse mode. - * Enabling the generation of individuals functions for reverse-mode - * can have a negative impact on the performance of the evaluation of the - * sparse hessian since Hessian symmetry will not be exploited. To - * improve performance one can request only the upper or lower elements - * of the hessian using setCustomSparseHessianElements(). - * - * @see setCustomSparseHessianElements() - * @see setSparseHessianReusesRev2() - * - * @param create true if source-code for a sparse Hessian should be - * created, false otherwise - */ - inline void setCreateSparseHessian(bool create) { - _sparseHessian = create; - } - - /** - * Determines whether or not the sparse Hessian should reuse functions - * generated for the reverse two pass. - * The sparse Hessian will only make use of the reverse two mode if both - * this flag is set to true and the reverseTwo mode is enabled. - * - * @return true if the functions created for reverse 2 mode should be - * reused to determine the sparse Hessian, false otherwise - */ - inline bool isSparseHessianReusesRev2() const { - return _sparseHessianReusesRev2; - } - - /** - * Defines whether or not the sparse Hessian should reuse functions - * generated for the reverse two pass. - * The sparse Hessian will only make use of the reverse two mode if both - * this flag is set to true and the reverseTwo mode is enabled. - * - * @param reuse true if the functions created for reverse 2 mode should be - * reused to determine the sparse Hessian, false otherwise - */ - inline void setSparseHessianReusesRev2(bool reuse) { - _sparseHessianReusesRev2 = reuse; - } - - /** - * Determines whether or not to generate source-code for a function that - * provides the Hessian sparsity pattern for each equation/dependent, - * when the sparse hessian creation is enabled. - * Even if this flag is set to false the function can still be generated - * if the second-order reverse mode is enabled. - * - * @return true if source-code for a Hessians sparsities patterns should - * be created, false otherwise - */ - inline bool isCreateHessianSparsityByEquation() const { - return _hessianByEquation; - } - - /** - * Defines whether or not to generate source-code for a function that - * provides the Hessian sparsity pattern for each equation/dependent, - * when the sparse hessian creation is enabled. - * Even if this flag is set to false the function can still be generated - * if the second-order reverse mode is enabled. - * - * @param create true if source-code for a Hessians sparsities should be - * created, false otherwise - */ - inline void setCreateHessianSparsityByEquation(bool create) { - _hessianByEquation = create; - } - - /** - * Determines whether or not to generate source-code for a function - * that evaluates a sparse Jacobian. If ReverseOne or ForwardOne - * functions are enabled, then the sparse Jacobian evaluation might - * use those functions. - * Enabling the generation of individuals functions for reverse-mode - * can have a small negative impact on the performance of the evaluation of - * the parse Jacobian. - - * @see setCustomSparseJacobianElements() - * - * @return true if source-code for a sparse Jacobian should be created, - * false otherwise - */ - inline bool isCreateSparseJacobian() const { - return _sparseJacobian; - } - - /** - * Defines whether or not to generate source-code for a function - * that evaluates a sparse Jacobian. If ReverseOne or ForwardOne - * functions are enabled, then the sparse Jacobian evaluation might - * use those functions. - * Enabling the generation of individuals functions for reverse-mode - * can have a small negative impact on the performance of the evaluation of - * the parse Jacobian. - - * @see setCustomSparseJacobianElements() - * - * @param create true if source-code for a sparse Jacobian should be - * created, false otherwise - */ - inline void setCreateSparseJacobian(bool create) { - _sparseJacobian = create; - } - - /** - * Determines whether or not the sparse Jacobian should reuse functions - * generated for the forward one or reverse one pass. - * The sparse Jacobian will only make use of these functions if both - * this flag is set to true and one of the forward one and reverse one - * mode is enabled. - * - * @return true if the functions created for forward or reverse 1 mode - * should be reused to determine the sparse Jacobian, false otherwise - */ - inline bool isSparseJacobianReuse1stOrderPasses() const { - return _sparseJacobianReusesOne; - } - - /** - * Defines whether or not the sparse Jacobian should reuse functions - * generated for the forward one or reverse one pass. - * The sparse Jacobian will only make use of these functions if both - * this flag is set to true and one of the forward one and reverse one - * mode is enabled. - * - * @param reuse true if the functions created for forward or reverse 1 mode - * should be reused to determine the sparse Jacobian, - * false otherwise - */ - inline void setSparseJacobianReuse1stOrderPasses(bool reuse) { - _sparseJacobianReusesOne = reuse; - } - - /** - * Determines whether or not to generate source-code for a function - * that evaluates the original model. - * - * @return true if source-code for the original model should be created, - * false otherwise - */ - inline bool isCreateForwardZero() const { - return _zero; - } - - /** - * Defines whether or not to generate source-code for a function - * that evaluates the original model. - * - * @return create true if source-code for the original model should be - * created, false otherwise - */ - inline void setCreateForwardZero(bool create) { - _zero = create; - } - - /** - * Determines whether or not to generate source-code for the - * first-order forward mode that is used for the evaluation of the - * Jacobian when the model is used through a user defined atomic - * AD function. - * Enabling the generation of individuals functions for forward-mode - * might have a small negative impact on the performance of the evaluation - * of the sparse Jacobian (if forward mode is selected). - * - * @see isCreateSparseJacobian() - * - * @return true if the generation of the source for first-order forward - * mode is enabled, false otherwise. - */ - inline bool isCreateSparseForwardOne() const { - return _forwardOne; - } - - /** - * Defines whether or not to generate source-code for the - * first-order forward mode that is used for the evaluation of the - * Jacobian when the model is used through a user defined atomic - * AD function. - * Enabling the generation of individuals functions for forward-mode - * might have a small negative impact on the performance of the evaluation - * of the sparse Jacobian (if forward-mode is selected). - * - * @see setCreateSparseJacobian() - * - * @param create true if the generation of the source for first-order - * forward mode is enabled, false otherwise. - */ - inline void setCreateForwardOne(bool create) { - _forwardOne = create; - } - - /** - * Determines whether or not to generate source-code for the - * first-order reverse mode that is used for the evaluation of the - * Jacobian when the model is used through a user defined atomic - * AD function. - * Enabling the generation of individuals functions for reverse-mode - * might have a small negative impact on the performance of the evaluation - * of the sparse Jacobian (if reverse-mode is selected). - * - * @see isCreateSparseJacobian() - * - * @return true if the generation of the source for first-order reverse - * mode is enabled, false otherwise. - */ - inline bool isCreateReverseOne() const { - return _reverseOne; - } - - /** - * Determines whether or not to generate source-code for the - * first-order reverse mode that is used for the evaluation of the - * Jacobian when the model is used through a user defined atomic - * AD function. - * Enabling the generation of individuals functions for reverse-mode - * might have a small negative impact on the performance of the evaluation - * of the sparse Jacobian (if reverse-mode is selected). - * - * @see setCreateSparseJacobian() - * - * @return true if the generation of the source for first-order reverse - * mode is enabled, false otherwise. - */ - inline void setCreateReverseOne(bool create) { - _reverseOne = create; - } - - /** - * Determines whether or not to generate source-code for the - * second-order reverse mode that is used for the evaluation of the - * hessian when the model is used through a user defined atomic - * AD function. - * Enabling the generation of individuals functions for reverse-mode - * can have a negative impact on the performance of the evaluation of the - * sparse hessian. - * - * Warning: only the values for px[j * (k+1)] will be defined, since - * px[j * (k+1) + 1] is not used during the hessian evaluation. - * - * @return true if the generation of the source for second-order reverse - * mode is enabled, false otherwise. - */ - inline bool isCreateReverseTwo() const { - return _reverseOne; - } - - /** - * Defines whether or not to enable the generation of the source-code - * for the second-order reverse mode that is used for the evaluation - * of the hessian when the model is used through a user defined atomic - * AD function. - * Enabling the generation of individuals functions for reverse-mode - * can have a negative impact on the performance of the evaluation of the - * hessian. To improve performance one can request only the upper or - * lower elements of the hessian using setCustomSparseHessianElements() - * and later only request those elements through the outer model (ADFun). - * - * Warning: only the values for px[j * (k+1)] will be defined, since - * px[j * (k+1) + 1] is not used during the hessian evaluation. - * - * @param create true to enable the generation of the source for - * second-order reverse mode, false otherwise. - */ - inline void setCreateReverseTwo(bool create) { - _reverseTwo = create; - } - - inline void setCustomSparseJacobianElements(const std::vector& row, - const std::vector& col) { - _custom_jac = Position(row, col); - } - - template - inline void setCustomSparseJacobianElements(const VectorSet& elements) { - _custom_jac = Position(elements); - } - - inline void setCustomSparseHessianElements(const std::vector& row, - const std::vector& col) { - _custom_hess = Position(row, col); - } - - template - inline void setCustomSparseHessianElements(const VectorSet& elements) { - _custom_hess = Position(elements); - } - - inline size_t getMaxAssignmentsPerFunc() const { - return _maxAssignPerFunc; - } - - inline void setMaxAssignmentsPerFunc(size_t maxAssignPerFunc) { - _maxAssignPerFunc = maxAssignPerFunc; - } - - inline virtual ~ModelCSourceGen() { - delete _funNoLoops; - delete _atomicsIndeps; - - for (LoopModel* it : _loopTapes) { - delete it; - } - } - -public: - static inline std::string baseTypeName(); - - template - static void generateFunctionDeclarationSource(std::ostringstream& cache, - const std::string& model_function, - const std::string& suffix, - const std::map& elements, - const std::string& argsDcl); - -protected: - - virtual VariableNameGenerator* createVariableNameGenerator(const std::string& depName = "y", - const std::string& indepName = "x", - const std::string& tmpName = "v", - const std::string& tmpArrayName = "array"); - - const std::map& getSources(MultiThreadingType multiThreadingType, - JobTimer* timer); - - virtual void generateSources(MultiThreadingType multiThreadingType, - JobTimer* timer = nullptr); - - virtual void generateLoops(); - - virtual void generateInfoSource(); - - virtual void generateAtomicFuncNames(); - - virtual bool isAtomicsUsed(); - - virtual const std::map >& getAtomicsIndeps(); - - /*********************************************************************** - * zero order (the original model) - **********************************************************************/ - - virtual void generateZeroSource(); - - /** - * Generates the operation graph for the zero order model with loops - */ - virtual std::vector prepareForward0WithLoops(CodeHandler& handler, - const std::vector& x); - - /*********************************************************************** - * Jacobian - **********************************************************************/ - - virtual void generateJacobianSource(); - - virtual void generateSparseJacobianSource(MultiThreadingType multiThreadingType); - - virtual void generateSparseJacobianSource(bool forward); - - virtual void generateSparseJacobianForRevSource(bool forward, - MultiThreadingType multiThreadingType); - - virtual std::string generateSparseJacobianForRevSingleThreadSource(const std::string& functionName, - std::map jacInfo, - size_t maxCompressedSize, - const std::string& functionRevFor, - const std::string& revForSuffix, - bool forward); - - virtual std::string generateSparseJacobianForRevMultiThreadSource(const std::string& functionName, - std::map jacInfo, - size_t maxCompressedSize, - const std::string& functionRevFor, - const std::string& revForSuffix, - bool forward, - MultiThreadingType multiThreadingType); - /** - * Generates a sparse Jacobian using loops. - * - * The original model is split into two models: - * - one for the repeated equations - * \f[ y_i = f(x_{l(j)}, x_v, z_k) \f] - * - and another for the equations which do not belong in a loop and the - * non-indexed temporary variables (\f$z\f$) used by \f$f\f$. - * \f[ z_k = g_k(x_v) \f] - * - * The jacobian elements for the equations in loops are evaluated as: - * \f[ \frac{\mathrm{d} y_i}{\mathrm{d} x_v} = - * \sum_k \left( \frac{\partial f_i}{\partial z_k} \frac{\partial z_k}{\partial x_v} \right) + - * \sum_j \left( \frac{\partial f_i}{\partial x_{l(j)}} \frac{\partial x_{l(j)}}{\partial x_v} \right) + - * \frac{\partial f_i}{\partial x_v} - * \f] - * - * @param handler The operation graph handler - * @param indVars The independent variables - * @return the operation graph for the compressed jacobin with loops - */ - virtual std::vector prepareSparseJacobianWithLoops(CodeHandler& handler, - const std::vector& x, - bool forward); - - inline void prepareSparseJacobianRowWithLoops(CodeHandler& handler, - LoopModel& lModel, - size_t tapeI, - const loops::JacobianWithLoopsRowInfo& rowInfo, - const std::vector >& dyiDxtape, - const std::vector >& dzDx, - const CGBase& py, - IndexOperationNode& iterationIndexOp, - std::vector >& ifElses, - size_t& jacLE, - std::vector, IndexPattern*> >& indexedLoopResults, - std::set& allLocations); - - inline void analyseSparseJacobianWithLoops(const std::vector& rows, - const std::vector& cols, - const std::vector& location, - SparsitySetType& noLoopEvalSparsity, - std::vector > >& noLoopEvalLocations, - std::map*, SparsitySetType>& loopsEvalSparsities, - std::map*, std::vector >& loopEqInfo); - - - virtual void generateSparseJacobianWithLoopsSourceFromForRev(const std::map& jacInfo, - size_t maxCompressedSize, - const std::string& localFunctionTypeName, - const std::string& suffix, - const std::string& keyName, - const std::map >& nonLoopElements, - const std::map*, std::map > > >& loopGroups, - void (*generateLocalFunctionName)(std::ostringstream& cache, const std::string& modelName, const LoopModel& loop, size_t g)); - - inline virtual void generateFunctionNameLoopFor1(std::ostringstream& cache, - const LoopModel& loop, - size_t g); - - inline static void generateFunctionNameLoopFor1(std::ostringstream& cache, - const std::string& modelName, - const LoopModel& loop, - size_t g); - - inline virtual void generateFunctionNameLoopRev1(std::ostringstream& cache, - const LoopModel& loop, - size_t i); - - inline static void generateFunctionNameLoopRev1(std::ostringstream& cache, - const std::string& modelName, - const LoopModel& loop, - size_t i); - - /*********************************************************************** - * Hessian - **********************************************************************/ - - virtual void generateHessianSource(); - - virtual void generateSparseHessianSource(MultiThreadingType multiThreadingType); - - virtual void generateSparseHessianSourceDirectly(); - - virtual void generateSparseHessianSourceFromRev2(MultiThreadingType multiThreadingType); - - virtual std::string generateSparseHessianRev2SingleThreadSource(const std::string& functionName, - std::map hessInfo, - size_t maxCompressedSize, - const std::string& functionRev2, - const std::string& rev2Suffix); - - virtual std::string generateSparseHessianRev2MultiThreadSource(const std::string& functionName, - std::map hessInfo, - size_t maxCompressedSize, - const std::string& functionRev2, - const std::string& rev2Suffix, - MultiThreadingType multiThreadingType); - - virtual void determineSecondOrderElements4Eval(std::vector& userRows, - std::vector& userCols); - - /** - * Loops - */ - /** - * Generates a sparse Hessian using loops. - * - * The original model is split into two models: - * - one for the repeated equations - * \f[ y_i = f(x_{l(j)}, x_v, z_k) \f] - * - and another for the equations which do not belong in a loop and - * the non-indexed temporary variables (\f$z\f$) used by \f$f\f$. - * \f[ z_k = g_k(x_v) \f] - * - * The Hessian elements for the equations in loops are evaluated as: - * \f[ \frac{\mathrm{d}^2 y_i}{\partial x_w \partial x_v} = - * \sum_k \left( \frac{\partial^2 f_i}{\partial x_w \partial z_k} \frac{\partial z_k}{\partial x_v} + - * \frac{\partial f_i}{\partial z_k} \frac{\partial^2 z_k}{\partial x_w \partial x_v} - * \right) + - * \sum_j \left( \frac{\partial^2 f_i}{\partial x_w \partial x_{l(j)}} \frac{\partial x_{l(j)}}{\partial x_v} \right) + - * \frac{\partial^2 f_i}{\partial x_w \partial x_v} - * \f] - * - * @param handler The operation graph handler - * @param indVars The independent variables - * @return the operation graph for the compressed jacobin with loops - */ - virtual std::vector prepareSparseHessianWithLoops(CodeHandler& handler, - std::vector& indVars, - std::vector& w, - const std::vector& lowerHessRows, - const std::vector& lowerHessCols, - const std::vector& lowerHessOrder, - const std::map& duplicates); - - inline void analyseSparseHessianWithLoops(const std::vector& lowerHessRows, - const std::vector& lowerHessCols, - const std::vector& lowerHessOrder, - SparsitySetType& noLoopEvalJacSparsity, - SparsitySetType& noLoopEvalHessSparsity, - std::vector > >& noLoopEvalHessLocations, - std::map*, loops::HessianWithLoopsInfo >& loopHessInfo, - bool useSymmetry); - - inline virtual void generateSparseHessianWithLoopsSourceFromRev2(const std::map& hessInfo, - size_t maxCompressedSize); - - inline virtual void generateFunctionNameLoopRev2(std::ostringstream& cache, - const LoopModel& loop, - size_t g); - - static inline void generateFunctionNameLoopRev2(std::ostringstream& cache, - const std::string& modelName, - const LoopModel& loop, - size_t g); - - /*********************************************************************** - * Sparsities for forward/reverse - **********************************************************************/ - - virtual void generateSparsity1DSource(const std::string& function, - const std::vector& sparsity); - - virtual void generateSparsity2DSource(const std::string& function, - const LocalSparsityInfo& sparsity); - - virtual void generateSparsity2DSource2(const std::string& function, - const std::vector& sparsities); - - virtual void generateSparsity1DSource2(const std::string& function, - const std::map >& rows); - - /*********************************************************************** - * Forward 1 mode - **********************************************************************/ - - virtual void generateSparseForwardOneSources(); - - virtual void generateSparseForwardOneSourcesWithAtomics(const std::map >& elements); - - virtual void generateSparseForwardOneSourcesNoAtomics(const std::map >& elements); - - virtual void generateForwardOneSources(); - - virtual void prepareSparseForwardOneWithLoops(const std::map >& elements); - - virtual void createForwardOneWithLoopsNL(CodeHandler& handler, - size_t j, - std::vector >& jacCol); - - - inline static std::map > > generateLoopFor1Jac(ADFun& fun, - const SparsitySetType& sparsity, - const SparsitySetType& evalSparsity, - const std::vector& xl, - bool constainsAtomics); - - /*********************************************************************** - * Reverse 1 mode - **********************************************************************/ - - virtual void generateSparseReverseOneSources(); - - virtual void generateSparseReverseOneSourcesWithAtomics(const std::map >& elements); - - virtual void generateSparseReverseOneSourcesNoAtomics(const std::map >& elements); - - virtual void generateReverseOneSources(); - - virtual void prepareSparseReverseOneWithLoops(const std::map >& elements); - - virtual void createReverseOneWithLoopsNL(CodeHandler& handler, - size_t i, - std::vector >& jacRow); - - inline static std::vector > generateLoopRev1Jac(ADFun& fun, - const SparsitySetType& sparsity, - const SparsitySetType& evalSparsity, - const std::vector& xl, - bool constainsAtomics); - - /*********************************************************************** - * Reverse 2 mode - **********************************************************************/ - - virtual void generateSparseReverseTwoSources(); - - virtual void generateSparseReverseTwoSourcesWithAtomics(const std::map >& elements); - - virtual void generateSparseReverseTwoSourcesNoAtomics(const std::map >& elements, - const std::vector& evalRows, - const std::vector& evalCols); - - virtual void generateReverseTwoSources(); - - virtual void generateGlobalDirectionalFunctionSource(const std::string& function, - const std::string& function2_suffix, - const std::string& function_sparsity, - const std::map >& elements); - - /** - * Loops - */ - virtual void prepareSparseReverseTwoWithLoops(const std::map >& elements); - - /*********************************************************************** - * Sparsities - **********************************************************************/ - - virtual void determineJacobianSparsity(); - - virtual void generateJacobianSparsitySource(); - - virtual void determineHessianSparsity(); - - /** - * Determines groups of rows from a sparsity pattern which do not share - * the same columns - * - * @param columns the column indexes of interest (all others are ignored); - * an empty set means all columns - * @param sparsity The sparsity pattern to color - * @return the colors - */ - inline std::vector::Color> colorByRow(const std::set& columns, - const SparsitySetType& sparsity); - - virtual void generateHessianSparsitySource(); - - - static inline std::map > > determineOrderByCol(const std::map >& elements, - const LocalSparsityInfo& sparsity); - - static inline std::map > > determineOrderByCol(const std::map >& elements, - const std::vector& userRows, - const std::vector& userCols); - - static inline std::vector > determineOrderByCol(size_t col, - const std::vector& colElements, - const std::vector& userRows, - const std::vector& userCols); - - static inline std::map > > determineOrderByRow(const std::map >& elements, - const LocalSparsityInfo& sparsity); - - static inline std::map > > determineOrderByRow(const std::map >& elements, - const std::vector& userRows, - const std::vector& userCols); - - static inline std::vector > determineOrderByRow(size_t row, - const std::vector& rowsElements, - const std::vector& userRows, - const std::vector& userCols); - - /*********************************************************************** - * Multi-threading - **********************************************************************/ - - /** - * - */ - static void printFileStartPThreads(std::ostringstream& cache, - const std::string& baseTypeName); - - static void printFunctionStartPThreads(std::ostringstream& cache, - size_t size); - - static void printFunctionEndPThreads(std::ostringstream& cache, - size_t size); - - static void printFileStartOpenMP(std::ostringstream& cache); - - static void printFunctionStartOpenMP(std::ostringstream& cache, - size_t size); - - static void printLoopStartOpenMP(std::ostringstream& cache, - size_t size); - - static void printLoopEndOpenMP(std::ostringstream& cache, - size_t size); - - /** - * - */ - inline void startingJob(const std::string& jobName, - const JobType& type = JobTypeHolder<>::DEFAULT); - - inline void finishedJob(); - - friend class - ModelLibraryCSourceGen; - - friend class - ModelLibraryProcessor; -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_for0.hpp b/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_for0.hpp deleted file mode 100644 index 43344f290..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_for0.hpp +++ /dev/null @@ -1,66 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_FOR0_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_FOR0_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -void ModelCSourceGen::generateZeroSource() { - const std::string jobName = "model (zero-order forward)"; - - startingJob("'" + jobName + "'", JobTimer::GRAPH); - - CodeHandler handler; - handler.setJobTimer(_jobTimer); - - std::vector indVars(_fun.Domain()); - handler.makeVariables(indVars); - if (_x.size() > 0) { - for (size_t i = 0; i < indVars.size(); i++) { - indVars[i].setValue(_x[i]); - } - } - - std::vector dep; - - if (_loopTapes.empty()) { - dep = _fun.Forward(0, indVars); - } else { - /** - * Contains loops - */ - dep = prepareForward0WithLoops(handler, indVars); - } - - finishedJob(); - - LanguageC langC(_baseTypeName); - langC.setMaxAssigmentsPerFunction(_maxAssignPerFunc, &_sources); - langC.setParameterPrecision(_parameterPrecision); - langC.setGenerateFunction(_name + "_" + FUNCTION_FORWAD_ZERO); - - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator()); - - handler.generateCode(code, langC, dep, *nameGen, _atomicFunctions, jobName); -} - - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_for1.hpp b/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_for1.hpp deleted file mode 100644 index 3f2edb40b..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_for1.hpp +++ /dev/null @@ -1,308 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_FOR1_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_FOR1_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -void ModelCSourceGen::generateSparseForwardOneSources() { - - determineJacobianSparsity(); - - // elements[var]{equations} - std::map > elements; - for (size_t e = 0; e < _jacSparsity.rows.size(); e++) { - elements[_jacSparsity.cols[e]].push_back(_jacSparsity.rows[e]); - } - - if (!_loopTapes.empty()) { - /** - * with loops - */ - prepareSparseForwardOneWithLoops(elements); - return; - } - - /** - * Generate one function for each dependent variable - */ - startingJob("'model (forward one)'", JobTimer::SOURCE_GENERATION); - - if (isAtomicsUsed()) { - generateSparseForwardOneSourcesWithAtomics(elements); - } else { - generateSparseForwardOneSourcesNoAtomics(elements); - } - - finishedJob(); - - _cache.str(""); - - generateGlobalDirectionalFunctionSource(FUNCTION_SPARSE_FORWARD_ONE, - "indep", - FUNCTION_FORWARD_ONE_SPARSITY, - elements); -} - -template -void ModelCSourceGen::generateSparseForwardOneSourcesWithAtomics(const std::map >& elements) { - using std::vector; - - /** - * Generate one function for each dependent variable - */ - size_t n = _fun.Domain(); - - vector dxv(n); - - const std::string jobName = "model (forward one)"; - startingJob("'" + jobName + "'", JobTimer::SOURCE_GENERATION); - - for (const auto& it : elements) { - size_t j = it.first; - const std::vector& rows = it.second; - - _cache.str(""); - _cache << "model (forward one, indep " << j << ")"; - const std::string subJobName = _cache.str(); - - startingJob("'" + subJobName + "'", JobTimer::GRAPH); - - CodeHandler handler; - handler.setJobTimer(_jobTimer); - - vector indVars(n); - handler.makeVariables(indVars); - if (_x.size() > 0) { - for (size_t i = 0; i < n; i++) { - indVars[i].setValue(_x[i]); - } - } - - CGBase dx; - handler.makeVariable(dx); - if (_x.size() > 0) { - dx.setValue(Base(1.0)); - } - - // TODO: consider caching the zero order coefficients somehow between calls - _fun.Forward(0, indVars); - dxv[j] = dx; - vector dy = _fun.Forward(1, dxv); - dxv[j] = Base(0); - CPPADCG_ASSERT_UNKNOWN(dy.size() == _fun.Range()); - - vector dyCustom; - for (size_t it2 : rows) { - dyCustom.push_back(dy[it2]); - } - - finishedJob(); - - LanguageC langC(_baseTypeName); - langC.setMaxAssigmentsPerFunction(_maxAssignPerFunc, &_sources); - langC.setParameterPrecision(_parameterPrecision); - _cache.str(""); - _cache << _name << "_" << FUNCTION_SPARSE_FORWARD_ONE << "_indep" << j; - langC.setGenerateFunction(_cache.str()); - - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("dy")); - LangCDefaultHessianVarNameGenerator nameGenHess(nameGen.get(), "dx", n); - - handler.generateCode(code, langC, dyCustom, nameGenHess, _atomicFunctions, subJobName); - } -} - -template -void ModelCSourceGen::generateSparseForwardOneSourcesNoAtomics(const std::map >& elements) { - using std::vector; - - /** - * Jacobian - */ - size_t n = _fun.Domain(); - - CodeHandler handler; - handler.setJobTimer(_jobTimer); - - vector x(n); - handler.makeVariables(x); - if (_x.size() > 0) { - for (size_t i = 0; i < n; i++) { - x[i].setValue(_x[i]); - } - } - - CGBase dx; - handler.makeVariable(dx); - if (_x.size() > 0) { - dx.setValue(Base(1.0)); - } - - vector jacFlat(_jacSparsity.rows.size()); - - CppAD::sparse_jacobian_work work; // temporary structure for CPPAD - _fun.SparseJacobianForward(x, _jacSparsity.sparsity, _jacSparsity.rows, _jacSparsity.cols, jacFlat, work); - - /** - * organize results - */ - std::map > jac; // by column - std::map > positions; // by column - - for (const auto& it : elements) { - size_t j = it.first; - const std::vector& column = it.second; - - jac[j].resize(column.size()); - std::map& pos = positions[j]; - - for (size_t e = 0; e < column.size(); e++) { - size_t i = column[e]; - pos[i] = e; - } - } - - for (size_t el = 0; el < _jacSparsity.rows.size(); el++) { - size_t i = _jacSparsity.rows[el]; - size_t j = _jacSparsity.cols[el]; - size_t e = positions[j].at(i); - - vector& column = jac[j]; - column[e] = jacFlat[el] * dx; - } - - /** - * Create source for each independent/column - */ - typename std::map >::iterator itJ; - for (itJ = jac.begin(); itJ != jac.end(); ++itJ) { - size_t j = itJ->first; - vector& dyCustom = itJ->second; - - _cache.str(""); - _cache << "model (forward one, indep " << j << ")"; - const std::string subJobName = _cache.str(); - - LanguageC langC(_baseTypeName); - langC.setMaxAssigmentsPerFunction(_maxAssignPerFunc, &_sources); - langC.setParameterPrecision(_parameterPrecision); - _cache.str(""); - _cache << _name << "_" << FUNCTION_SPARSE_FORWARD_ONE << "_indep" << j; - langC.setGenerateFunction(_cache.str()); - - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("dy")); - LangCDefaultHessianVarNameGenerator nameGenHess(nameGen.get(), "dx", n); - - handler.generateCode(code, langC, dyCustom, nameGenHess, _atomicFunctions, subJobName); - } -} - -template -void ModelCSourceGen::generateForwardOneSources() { - - size_t m = _fun.Range(); - size_t n = _fun.Domain(); - - _cache.str(""); - _cache << _name << "_" << FUNCTION_FORWARD_ONE; - std::string model_function(_cache.str()); - - LanguageC langC(_baseTypeName); - std::string argsDcl = langC.generateDefaultFunctionArgumentsDcl(); - std::string args = langC.generateDefaultFunctionArguments(); - - _cache.str(""); - _cache << "#include \n" - << LanguageC::ATOMICFUN_STRUCT_DEFINITION << "\n" - "\n" - "void " << _name << "_" << FUNCTION_SPARSE_FORWARD_ONE << "(unsigned long pos, " << argsDcl << ");\n" - "void " << _name << "_" << FUNCTION_FORWARD_ONE_SPARSITY << "(unsigned long pos, unsigned long const** elements, unsigned long* nnz);\n" - "\n" - "int " << model_function << "(" - << _baseTypeName << " const tx[], " - << _baseTypeName << " ty[], " - << langC.generateArgumentAtomicDcl() << ") {\n" - " unsigned long ePos, ej, i, j, nnz, nnzMax;\n" - " unsigned long const* pos;\n" - " unsigned long* txPos;\n" - " unsigned long nnzTx;\n" - " " << _baseTypeName << " const * in[2];\n" - " " << _baseTypeName << "* out[1];\n" - " " << _baseTypeName << " x[" << n << "];\n" - " " << _baseTypeName << "* compressed;\n" - "\n" - " txPos = 0;\n" - " nnzTx = 0;\n" - " nnzMax = 0;\n" - " for (j = 0; j < " << n << "; j++) {\n" - " if (tx[j * 2 + 1] != 0.0) {\n" - " nnzTx++;\n" - " txPos = (unsigned long*) realloc(txPos, nnzTx * sizeof(unsigned long));\n" - " txPos[nnzTx - 1] = j;\n" - " " << _name << "_" << FUNCTION_FORWARD_ONE_SPARSITY << "(j, &pos, &nnz);\n" - " if(nnz > nnzMax)\n" - " nnzMax = nnz;\n" - " }\n" - " }\n" - " for (i = 0; i < " << m << "; i++) {\n" - " ty[i * 2 + 1] = 0;\n" - " }\n" - "\n" - " if (nnzTx == 0) {\n" - " free(txPos);\n" - " return 0; //nothing to do\n" - " }\n" - "\n" - " compressed = (" << _baseTypeName << "*) malloc(nnzMax * sizeof(" << _baseTypeName << "));\n" - "\n" - " for (j = 0; j < " << n << "; j++)\n" - " x[j] = tx[j * 2];\n" - "\n" - " for (ej = 0; ej < nnzTx; ej++) {\n" - " j = txPos[ej];\n" - " " << _name << "_" << FUNCTION_FORWARD_ONE_SPARSITY << "(j, &pos, &nnz);\n" - "\n" - " in[0] = x;\n" - " in[1] = &tx[j * 2 + 1];\n" - " out[0] = compressed;\n"; - if (!_loopTapes.empty()) { - _cache << " for(ePos = 0; ePos < nnz; ePos++)\n" - " compressed[ePos] = 0;\n" - "\n"; - } - _cache << " " << _name << "_" << FUNCTION_SPARSE_FORWARD_ONE << "(j, " << args << ");\n" - "\n" - " for (ePos = 0; ePos < nnz; ePos++) {\n" - " ty[pos[ePos] * 2 + 1] += compressed[ePos];\n" - " }\n" - "\n" - " }\n" - " free(compressed);\n" - " free(txPos);\n" - " return 0;\n" - "}\n"; - _sources[model_function + ".c"] = _cache.str(); - _cache.str(""); -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_hes.hpp b/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_hes.hpp deleted file mode 100644 index 4e0198ae5..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_hes.hpp +++ /dev/null @@ -1,673 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_HES_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_HES_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -void ModelCSourceGen::generateHessianSource() { - using std::vector; - - const std::string jobName = "Hessian"; - - startingJob("'" + jobName + "'", JobTimer::GRAPH); - - CodeHandler handler; - handler.setJobTimer(_jobTimer); - - size_t m = _fun.Range(); - size_t n = _fun.Domain(); - - - // independent variables - vector indVars(n); - handler.makeVariables(indVars); - if (_x.size() > 0) { - for (size_t i = 0; i < n; i++) { - indVars[i].setValue(_x[i]); - } - } - - // multipliers - vector w(m); - handler.makeVariables(w); - if (_x.size() > 0) { - for (size_t i = 0; i < m; i++) { - w[i].setValue(Base(1.0)); - } - } - - vector hess = _fun.Hessian(indVars, w); - - // make use of the symmetry of the Hessian in order to reduce operations - for (size_t i = 0; i < n; i++) { - for (size_t j = 0; j < i; j++) { - hess[i * n + j] = hess[j * n + i]; - } - } - - finishedJob(); - - LanguageC langC(_baseTypeName); - langC.setMaxAssigmentsPerFunction(_maxAssignPerFunc, &_sources); - langC.setParameterPrecision(_parameterPrecision); - langC.setGenerateFunction(_name + "_" + FUNCTION_HESSIAN); - - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("hess")); - LangCDefaultHessianVarNameGenerator nameGenHess(nameGen.get(), n); - - handler.generateCode(code, langC, hess, nameGenHess, _atomicFunctions, jobName); -} - -template -void ModelCSourceGen::generateSparseHessianSource(MultiThreadingType multiThreadingType) { - /** - * Determine the sparsity pattern p for Hessian of w^T F - */ - determineHessianSparsity(); - - if (_sparseHessianReusesRev2 && _reverseTwo) { - generateSparseHessianSourceFromRev2(multiThreadingType); - } else { - generateSparseHessianSourceDirectly(); - } -} - -template -void ModelCSourceGen::generateSparseHessianSourceDirectly() { - using std::vector; - - const std::string jobName = "sparse Hessian"; - size_t m = _fun.Range(); - size_t n = _fun.Domain(); - - /** - * we might have to consider a slightly different order than the one - * specified by the user according to the available elements in the sparsity - */ - std::vector evalRows, evalCols; - determineSecondOrderElements4Eval(evalRows, evalCols); - - std::map > locations; - for (size_t e = 0; e < evalRows.size(); e++) { - size_t j1 = evalRows[e]; - size_t j2 = evalCols[e]; - std::map >::iterator itJ1 = locations.find(j1); - if (itJ1 == locations.end()) { - locations[j1][j2] = e; - } else { - std::map& j22e = itJ1->second; - if (j22e.find(j2) == j22e.end()) { - j22e[j2] = e; // OK - } else { - // repeated elements not allowed - throw CGException("Repeated Hessian element requested: ", j1, " ", j2); - } - } - } - - // make use of the symmetry of the Hessian in order to reduce operations - std::vector lowerHessRows, lowerHessCols, lowerHessOrder; - lowerHessRows.reserve(_hessSparsity.rows.size() / 2); - lowerHessCols.reserve(lowerHessRows.size()); - lowerHessOrder.reserve(lowerHessRows.size()); - - std::map duplicates; // the elements determined using symmetry - std::map >::const_iterator itJ; - std::map::const_iterator itI; - for (size_t e = 0; e < evalRows.size(); e++) { - bool add = true; - size_t i = evalRows[e]; - size_t j = evalCols[e]; - if (i < j) { - // find the symmetric value - itJ = locations.find(j); - if (itJ != locations.end()) { - itI = itJ->second.find(i); - if (itI != itJ->second.end()) { - size_t eSim = itI->second; - duplicates[e] = eSim; - add = false; // symmetric value being determined - } - } - } - - if (add) { - lowerHessRows.push_back(i); - lowerHessCols.push_back(j); - lowerHessOrder.push_back(e); - } - } - - /** - * - */ - startingJob("'" + jobName + "'", JobTimer::GRAPH); - - CodeHandler handler; - handler.setJobTimer(_jobTimer); - - // independent variables - vector indVars(n); - handler.makeVariables(indVars); - if (_x.size() > 0) { - for (size_t i = 0; i < n; i++) { - indVars[i].setValue(_x[i]); - } - } - - // multipliers - vector w(m); - handler.makeVariables(w); - if (_x.size() > 0) { - for (size_t i = 0; i < m; i++) { - w[i].setValue(Base(1.0)); - } - } - - vector hess(_hessSparsity.rows.size()); - if (_loopTapes.empty()) { - CppAD::sparse_hessian_work work; - // "cppad.symmetric" may have missing values for functions using atomic - // functions which only provide half of the elements - // (some values could be zeroed) - work.color_method = "cppad.general"; - vector lowerHess(lowerHessRows.size()); - _fun.SparseHessian(indVars, w, _hessSparsity.sparsity, lowerHessRows, lowerHessCols, lowerHess, work); - - for (size_t i = 0; i < lowerHessOrder.size(); i++) { - hess[lowerHessOrder[i]] = lowerHess[i]; - } - - // make use of the symmetry of the Hessian in order to reduce operations - for (const auto& it2 : duplicates) { - hess[it2.first] = hess[it2.second]; - } - } else { - /** - * with loops - */ - hess = prepareSparseHessianWithLoops(handler, indVars, w, - lowerHessRows, lowerHessCols, lowerHessOrder, - duplicates); - } - - finishedJob(); - - LanguageC langC(_baseTypeName); - langC.setMaxAssigmentsPerFunction(_maxAssignPerFunc, &_sources); - langC.setParameterPrecision(_parameterPrecision); - langC.setGenerateFunction(_name + "_" + FUNCTION_SPARSE_HESSIAN); - - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("hess")); - LangCDefaultHessianVarNameGenerator nameGenHess(nameGen.get(), n); - - handler.generateCode(code, langC, hess, nameGenHess, _atomicFunctions, jobName); -} - -template -void ModelCSourceGen::generateSparseHessianSourceFromRev2(MultiThreadingType multiThreadingType) { - using namespace std; - - /** - * we might have to consider a slightly different order than the one - * specified by the user according to the available elements in the sparsity - */ - std::vector evalRows, evalCols; - determineSecondOrderElements4Eval(evalRows, evalCols); - - std::map hessInfo; - - // elements[var]{var} - for (size_t e = 0; e < evalRows.size(); e++) { - hessInfo[evalRows[e]].indexes.push_back(evalCols[e]); - } - - // maps each element to its position in the user hessian - for (auto& it : hessInfo) { - it.second.locations = determineOrderByRow(it.first, it.second.indexes, evalRows, evalCols); - } - - /** - * determine to which functions we can provide the hessian row directly - * without needing a temporary array (compressed) - */ - for (auto& it : hessInfo) { - const std::vector& els = it.second.indexes; - const std::vector >& location = it.second.locations; - CPPADCG_ASSERT_UNKNOWN(els.size() == location.size()); - CPPADCG_ASSERT_UNKNOWN(els.size() > 0); - - bool passed = true; - size_t hessRowStart = *location[0].begin(); - for (size_t e = 0; e < els.size(); e++) { - if (location[e].size() > 1) { - passed = false; // too many elements - break; - } - if (*location[e].begin() != hessRowStart + e) { - passed = false; // wrong order - break; - } - } - it.second.ordered = passed; - } - - /** - * determine the maximum size of the temporary array - */ - size_t maxCompressedSize = 0; - - for (const auto& it : hessInfo) { - if (it.second.indexes.size() > maxCompressedSize && !it.second.ordered) - maxCompressedSize = it.second.indexes.size(); - } - - if (!_loopTapes.empty()) { - /** - * with loops - */ - generateSparseHessianWithLoopsSourceFromRev2(hessInfo, maxCompressedSize); - return; - } - - string functionName = _name + "_" + FUNCTION_SPARSE_HESSIAN; - string functionRev2 = _name + "_" + FUNCTION_SPARSE_REVERSE_TWO; - string rev2Suffix = "indep"; - - if (!_multiThreading || multiThreadingType == MultiThreadingType::NONE) { - _sources[functionName + ".c"] = generateSparseHessianRev2SingleThreadSource(functionName, hessInfo, maxCompressedSize, functionRev2, rev2Suffix); - } else { - _sources[functionName + ".c"] = generateSparseHessianRev2MultiThreadSource(functionName, hessInfo, maxCompressedSize, functionRev2, rev2Suffix, multiThreadingType); - } - _cache.str(""); -} - -template -std::string ModelCSourceGen::generateSparseHessianRev2SingleThreadSource(const std::string& functionName, - std::map hessInfo, - size_t maxCompressedSize, - const std::string& functionRev2, - const std::string& rev2Suffix) { - LanguageC langC(_baseTypeName); - std::string argsDcl = langC.generateDefaultFunctionArgumentsDcl(); - - _cache.str(""); - _cache << "#include \n" - << LanguageC::ATOMICFUN_STRUCT_DEFINITION << "\n\n"; - generateFunctionDeclarationSource(_cache, functionRev2, rev2Suffix, hessInfo, argsDcl); - _cache << "\n" - "void " << functionName << "(" << argsDcl << ") {\n" - " " << _baseTypeName << " const * inLocal[3];\n" - " " << _baseTypeName << " inLocal1 = 1;\n" - " " << _baseTypeName << " * outLocal[1];\n"; - if (maxCompressedSize > 0) { - _cache << " " << _baseTypeName << " compressed[" << maxCompressedSize << "];\n"; - } - _cache << " " << _baseTypeName << " * hess = out[0];\n" - "\n" - " inLocal[0] = in[0];\n" - " inLocal[1] = &inLocal1;\n" - " inLocal[2] = in[1];\n"; - if (maxCompressedSize > 0) { - _cache << " outLocal[0] = compressed;"; - } - - langC.setArgumentIn("inLocal"); - langC.setArgumentOut("outLocal"); - std::string argsLocal = langC.generateDefaultFunctionArguments(); - bool previousCompressed = true; - for (auto& it : hessInfo) { - size_t index = it.first; - const std::vector& els = it.second.indexes; - const std::vector >& location = it.second.locations; - CPPADCG_ASSERT_UNKNOWN(els.size() == location.size()); - CPPADCG_ASSERT_UNKNOWN(els.size() > 0); - - _cache << "\n"; - bool compressed = !it.second.ordered; - if (!compressed) { - _cache << " outLocal[0] = &hess[" << *location[0].begin() << "];\n"; - } else if (!previousCompressed) { - _cache << " outLocal[0] = compressed;\n"; - } - _cache << " " << functionRev2 << "_" << rev2Suffix << index << "(" << argsLocal << ");\n"; - if (compressed) { - for (size_t e = 0; e < els.size(); e++) { - _cache << " "; - for (size_t itl : location[e]) { - _cache << "hess[" << itl << "] = "; - } - _cache << "compressed[" << e << "];\n"; - } - } - previousCompressed = compressed; - } - - _cache << "\n" - "}\n"; - return _cache.str(); -} - - -template -std::string ModelCSourceGen::generateSparseHessianRev2MultiThreadSource(const std::string& functionName, - std::map hessInfo, - size_t maxCompressedSize, - const std::string& functionRev2, - const std::string& rev2Suffix, - MultiThreadingType multiThreadingType) { - CPPADCG_ASSERT_UNKNOWN(_multiThreading); - CPPADCG_ASSERT_UNKNOWN(multiThreadingType != MultiThreadingType::NONE); - - LanguageC langC(_baseTypeName); - std::string argsDcl = langC.generateDefaultFunctionArgumentsDcl(); - - _cache.str(""); - _cache << "#include \n" - << LanguageC::ATOMICFUN_STRUCT_DEFINITION << "\n\n"; - generateFunctionDeclarationSource(_cache, functionRev2, rev2Suffix, hessInfo, argsDcl); - - - langC.setArgumentIn("inLocal"); - langC.setArgumentOut("outLocal"); - std::string argsLocal = langC.generateDefaultFunctionArguments(); - - /** - * Create independent functions for each row/column of the Jacobian - */ - for (const auto& it : hessInfo) { - size_t index = it.first; - const std::vector& els = it.second.indexes; - const std::vector >& location = it.second.locations; - CPPADCG_ASSERT_UNKNOWN(els.size() == location.size()); - - bool compressed = !it.second.ordered; - if (!compressed) { - continue; - } - - _cache << "void " << functionRev2 << "_" << rev2Suffix << index << "_wrap(" << argsDcl << ") {\n" - " " << _baseTypeName << " const * inLocal[3];\n" - " " << _baseTypeName << " inLocal1 = 1;\n" - " " << _baseTypeName << " * outLocal[1];\n" - " " << _baseTypeName << " compressed[" << it.second.indexes.size() << "];\n" - " " << _baseTypeName << " * hess = out[0];\n" - "\n" - " inLocal[0] = in[0];\n" - " inLocal[1] = &inLocal1;\n" - " inLocal[2] = in[1];\n" - " outLocal[0] = compressed;\n"; - _cache << " " << functionRev2 << "_" << rev2Suffix << index << "(" << argsLocal << ");\n"; - for (size_t e = 0; e < els.size(); e++) { - _cache << " "; - for (size_t itl : location[e]) { - _cache << "hess[" << itl << "] = "; - } - _cache << "compressed[" << e << "];\n"; - } - _cache << "}\n"; - } - - _cache << "\n" - "typedef void (*cppadcg_function_type) (" << argsDcl << ");\n"; - - - if (multiThreadingType == MultiThreadingType::OPENMP) { - _cache << "\n"; - printFileStartOpenMP(_cache); - _cache << "\n"; - - } else { - /** - * PThreads pool needs a function with a void pointer argument - */ - assert(multiThreadingType == MultiThreadingType::PTHREADS); - - printFileStartPThreads(_cache, _baseTypeName); - } - - /** - * Hessian function - */ - _cache << "\n" - "void " << functionName << "(" << argsDcl << ") {\n" - " static const cppadcg_function_type p[" << hessInfo.size() << "] = {"; - for (const auto& it : hessInfo) { - size_t index = it.first; - if (index != hessInfo.begin()->first) _cache << ", "; - if (it.second.ordered) { - _cache << functionRev2 << "_" << rev2Suffix << index; - } else { - _cache << functionRev2 << "_" << rev2Suffix << index << "_wrap"; - } - } - _cache << "};\n" - " static const long offset["<< hessInfo.size() <<"] = {"; - for (const auto& it : hessInfo) { - if (it.first != hessInfo.begin()->first) _cache << ", "; - if (it.second.ordered) { - _cache << *it.second.locations[0].begin(); - } else { - _cache << "0"; - } - } - _cache << "};\n" - " " << _baseTypeName << " inLocal1 = 1;\n" - " " << _baseTypeName << " const * inLocal[3] = {in[0], &inLocal1, in[1]};\n" - " " << _baseTypeName << " * outLocal[1];\n"; - _cache << " " << _baseTypeName << " * hess = out[0];\n" - " long i;\n" - "\n"; - - if(multiThreadingType == MultiThreadingType::OPENMP) { - printFunctionStartOpenMP(_cache, hessInfo.size()); - _cache << "\n"; - printLoopStartOpenMP(_cache, hessInfo.size()); - _cache << " outLocal[0] = &hess[offset[i]];\n" - " (*p[i])(" << argsLocal << ");\n"; - printLoopEndOpenMP(_cache, hessInfo.size()); - _cache << "\n"; - - } else { - assert(multiThreadingType == MultiThreadingType::PTHREADS); - - printFunctionStartPThreads(_cache, hessInfo.size()); - _cache << "\n" - " for(i = 0; i < " << hessInfo.size() << "; ++i) {\n" - " args[i] = (ExecArgStruct*) malloc(sizeof(ExecArgStruct));\n" - " args[i]->func = p[i];\n" - " args[i]->in = inLocal;\n" - " args[i]->out[0] = &hess[offset[i]];\n" - " args[i]->atomicFun = " << langC .getArgumentAtomic() << ";\n" - " }\n" - "\n"; - printFunctionEndPThreads(_cache, hessInfo.size()); - } - - _cache << "\n" - "}\n"; - return _cache.str(); -} - -template -void ModelCSourceGen::determineSecondOrderElements4Eval(std::vector& evalRows, - std::vector& evalCols) { - /** - * Atomic functions migth not have all the elements and thus there may - * be no symmetry. This will explore symmetry in order to provide the - * second order elements requested by the user. - */ - evalRows.reserve(_hessSparsity.rows.size()); - evalCols.reserve(_hessSparsity.cols.size()); - - for (size_t e = 0; e < _hessSparsity.rows.size(); e++) { - size_t i = _hessSparsity.rows[e]; - size_t j = _hessSparsity.cols[e]; - if (_hessSparsity.sparsity[i].find(j) == _hessSparsity.sparsity[i].end() && - _hessSparsity.sparsity[j].find(i) != _hessSparsity.sparsity[j].end()) { - // only the symmetric value is available - // (it can be caused by atomic functions which may only be providing a partial hessian) - evalRows.push_back(j); - evalCols.push_back(i); - } else { - evalRows.push_back(i); - evalCols.push_back(j); - } - } -} - -template -void ModelCSourceGen::determineHessianSparsity() { - if (_hessSparsity.sparsity.size() > 0) { - return; - } - - size_t m = _fun.Range(); - size_t n = _fun.Domain(); - - /** - * sparsity for the sum of the hessians of all equations - */ - SparsitySetType r(n); // identity matrix - for (size_t j = 0; j < n; j++) - r[j].insert(j); - SparsitySetType jac = _fun.ForSparseJac(n, r); - - SparsitySetType s(1); - for (size_t i = 0; i < m; i++) { - s[0].insert(i); - } - _hessSparsity.sparsity = _fun.RevSparseHes(n, s, false); - //printSparsityPattern(_hessSparsity.sparsity, "hessian"); - - if (_hessianByEquation || _reverseTwo) { - /** - * sparsity for the hessian of each equations - */ - - std::set customVarsInHess; - if (_custom_hess.defined) { - customVarsInHess.insert(_custom_hess.row.begin(), _custom_hess.row.end()); - customVarsInHess.insert(_custom_hess.col.begin(), _custom_hess.col.end()); - - r = SparsitySetType(n); //clear r - for (size_t j : customVarsInHess) { - r[j].insert(j); - } - jac = _fun.ForSparseJac(n, r); - } - - /** - * Coloring - */ - const std::vector colors = colorByRow(customVarsInHess, jac); - - /** - * For each individual equation - */ - _hessSparsities.resize(m); - for (size_t i = 0; i < m; i++) { - _hessSparsities[i].sparsity.resize(n); - } - - for (size_t c = 0; c < colors.size(); c++) { - const Color& color = colors[c]; - - // first-order - r = SparsitySetType(n); //clear r - for (size_t j : color.forbiddenRows) { - r[j].insert(j); - } - _fun.ForSparseJac(n, r); - - // second-order - s[0].clear(); - const std::set& equations = color.rows; - for (size_t i : equations) { - s[0].insert(i); - } - - SparsitySetType sparsityc = _fun.RevSparseHes(n, s, false); - - /** - * Retrieve the individual hessians for each equation - */ - const std::map& var2Eq = color.column2Row; - for (size_t j : color.forbiddenRows) { //used variables - if (sparsityc[j].size() > 0) { - size_t i = var2Eq.at(j); - _hessSparsities[i].sparsity[j].insert(sparsityc[j].begin(), - sparsityc[j].end()); - } - } - - } - - for (size_t i = 0; i < m; i++) { - LocalSparsityInfo& hessSparsitiesi = _hessSparsities[i]; - - if (!_custom_hess.defined) { - generateSparsityIndexes(hessSparsitiesi.sparsity, - hessSparsitiesi.rows, hessSparsitiesi.cols); - - } else { - size_t nnz = _custom_hess.row.size(); - for (size_t e = 0; e < nnz; e++) { - size_t i1 = _custom_hess.row[e]; - size_t i2 = _custom_hess.col[e]; - if (hessSparsitiesi.sparsity[i1].find(i2) != hessSparsitiesi.sparsity[i1].end()) { - hessSparsitiesi.rows.push_back(i1); - hessSparsitiesi.cols.push_back(i2); - } - } - } - } - - } - - if (!_custom_hess.defined) { - generateSparsityIndexes(_hessSparsity.sparsity, - _hessSparsity.rows, _hessSparsity.cols); - - } else { - _hessSparsity.rows = _custom_hess.row; - _hessSparsity.cols = _custom_hess.col; - } -} - -template -void ModelCSourceGen::generateHessianSparsitySource() { - determineHessianSparsity(); - - generateSparsity2DSource(_name + "_" + FUNCTION_HESSIAN_SPARSITY, _hessSparsity); - _sources[_name + "_" + FUNCTION_HESSIAN_SPARSITY + ".c"] = _cache.str(); - _cache.str(""); - - if (_hessianByEquation || _reverseTwo) { - generateSparsity2DSource2(_name + "_" + FUNCTION_HESSIAN_SPARSITY2, _hessSparsities); - _sources[_name + "_" + FUNCTION_HESSIAN_SPARSITY2 + ".c"] = _cache.str(); - _cache.str(""); - } -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_impl.hpp b/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_impl.hpp deleted file mode 100644 index 68279fc53..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_impl.hpp +++ /dev/null @@ -1,763 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_IMPL_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_IMPL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include -#include - -namespace CppAD { -namespace cg { - -template -const std::string ModelCSourceGen::FUNCTION_FORWAD_ZERO = "forward_zero"; - -template -const std::string ModelCSourceGen::FUNCTION_JACOBIAN = "jacobian"; - -template -const std::string ModelCSourceGen::FUNCTION_HESSIAN = "hessian"; - -template -const std::string ModelCSourceGen::FUNCTION_FORWARD_ONE = "forward_one"; - -template -const std::string ModelCSourceGen::FUNCTION_REVERSE_ONE = "reverse_one"; - -template -const std::string ModelCSourceGen::FUNCTION_REVERSE_TWO = "reverse_two"; - -template -const std::string ModelCSourceGen::FUNCTION_SPARSE_JACOBIAN = "sparse_jacobian"; - -template -const std::string ModelCSourceGen::FUNCTION_SPARSE_HESSIAN = "sparse_hessian"; - -template -const std::string ModelCSourceGen::FUNCTION_JACOBIAN_SPARSITY = "jacobian_sparsity"; - -template -const std::string ModelCSourceGen::FUNCTION_HESSIAN_SPARSITY = "hessian_sparsity"; - -template -const std::string ModelCSourceGen::FUNCTION_HESSIAN_SPARSITY2 = "hessian_sparsity2"; - -template -const std::string ModelCSourceGen::FUNCTION_SPARSE_FORWARD_ONE = "sparse_forward_one"; - -template -const std::string ModelCSourceGen::FUNCTION_SPARSE_REVERSE_ONE = "sparse_reverse_one"; - -template -const std::string ModelCSourceGen::FUNCTION_SPARSE_REVERSE_TWO = "sparse_reverse_two"; - -template -const std::string ModelCSourceGen::FUNCTION_FORWARD_ONE_SPARSITY = "forward_one_sparsity"; - -template -const std::string ModelCSourceGen::FUNCTION_REVERSE_ONE_SPARSITY = "reverse_one_sparsity"; - -template -const std::string ModelCSourceGen::FUNCTION_REVERSE_TWO_SPARSITY = "sparse_reverse_two_sparsity"; - -template -const std::string ModelCSourceGen::FUNCTION_INFO = "info"; - -template -const std::string ModelCSourceGen::FUNCTION_ATOMIC_FUNC_NAMES = "atomic_functions"; - -template -const std::string ModelCSourceGen::CONST = "const"; - -template -VariableNameGenerator* ModelCSourceGen::createVariableNameGenerator(const std::string& depName, - const std::string& indepName, - const std::string& tmpName, - const std::string& tmpArrayName) { - return new LangCDefaultVariableNameGenerator (depName, indepName, tmpName, tmpArrayName); -} - -template -const std::map& ModelCSourceGen::getSources(MultiThreadingType multiThreadingType, - JobTimer* timer) { - if (_sources.empty()) { - generateSources(multiThreadingType, timer); - } - return _sources; -} - -template -void ModelCSourceGen::generateSources(MultiThreadingType multiThreadingType, - JobTimer* timer) { - _jobTimer = timer; - - generateLoops(); - - startingJob("'" + _name + "'", JobTimer::SOURCE_FOR_MODEL); - - if (_zero) { - generateZeroSource(); - _zeroEvaluated = true; - } - - if (_jacobian) { - generateJacobianSource(); - } - - if (_hessian) { - generateHessianSource(); - } - - if (_forwardOne) { - generateSparseForwardOneSources(); - generateForwardOneSources(); - } - - if (_reverseOne) { - generateSparseReverseOneSources(); - generateReverseOneSources(); - } - - if (_reverseTwo) { - generateSparseReverseTwoSources(); - generateReverseTwoSources(); - } - - if (_sparseJacobian) { - generateSparseJacobianSource(multiThreadingType); - } - - if (_sparseHessian) { - generateSparseHessianSource(multiThreadingType); - } - - if (_sparseJacobian || _forwardOne || _reverseOne) { - generateJacobianSparsitySource(); - } - - if (_sparseHessian || _reverseTwo) { - generateHessianSparsitySource(); - } - - generateInfoSource(); - - generateAtomicFuncNames(); - - finishedJob(); -} - -template -void ModelCSourceGen::generateLoops() { - if (_relatedDepCandidates.empty()) { - return; //nothing to do - } - - startingJob("", JobTimer::LOOP_DETECTION); - - CodeHandler handler; - handler.setJobTimer(_jobTimer); - - std::vector xx(_fun.Domain()); - handler.makeVariables(xx); - if (_x.size() > 0) { - for (size_t i = 0; i < xx.size(); i++) { - xx[i].setValue(_x[i]); - } - } - - std::vector yy = _fun.Forward(0, xx); - - DependentPatternMatcher matcher(_relatedDepCandidates, yy, xx); - matcher.generateTapes(_funNoLoops, _loopTapes); - - finishedJob(); - if (_jobTimer != nullptr && _jobTimer->isVerbose()) { - std::cout << " equation patterns: " << matcher.getEquationPatterns().size() << - " loops: " << matcher.getLoops().size() << std::endl; - } -} - -template -void ModelCSourceGen::generateInfoSource() { - const char* localBaseName = typeid (Base).name(); - - std::string funcName = _name + "_" + FUNCTION_INFO; - - std::unique_ptr > nameGen(createVariableNameGenerator()); - - _cache.str(""); - _cache << "void " << funcName << "(const char** baseName, unsigned long* m, unsigned long* n, unsigned int* indCount, unsigned int* depCount) {\n" - " *baseName = \"" << _baseTypeName << " " << localBaseName << "\";\n" - " *m = " << _fun.Range() << ";\n" - " *n = " << _fun.Domain() << ";\n" - " *depCount = " << nameGen->getDependent().size() << "; // number of dependent array variables\n" - " *indCount = " << nameGen->getIndependent().size() << "; // number of independent array variables\n" - "}\n\n"; - - _sources[funcName + ".c"] = _cache.str(); -} - -template -void ModelCSourceGen::generateAtomicFuncNames() { - std::string funcName = _name + "_" + FUNCTION_ATOMIC_FUNC_NAMES; - size_t n = _atomicFunctions.size(); - _cache.str(""); - _cache << "void " << funcName << "(const char*** names, unsigned long* n) {\n" - " static const char* atomic[" << n << "] = {"; - for (size_t i = 0; i < n; i++) { - if (i > 0)_cache << ", "; - _cache << "\"" << _atomicFunctions[i] << "\""; - } - _cache << "};\n" - " *names = atomic;\n" - " *n = " << n << ";\n" - "}\n\n"; - - _sources[funcName + ".c"] = _cache.str(); -} - -template -bool ModelCSourceGen::isAtomicsUsed() { - if (_zeroEvaluated) { - return _atomicFunctions.size() > 0; - } else { - return !getAtomicsIndeps().empty(); - } -} - -template -const std::map >& ModelCSourceGen::getAtomicsIndeps() { - if (_atomicsIndeps == nullptr) { - AtomicDependencyLocator adl(_fun); - _atomicsIndeps = new std::map >(adl.findAtomicsUsage()); - } - return *_atomicsIndeps; -} - -template -std::vector::Color> ModelCSourceGen::colorByRow(const std::set& columns, - const SparsitySetType& sparsity) { - std::vector colors(sparsity.size()); // reserve the maximum size to avoid reallocating more space later - - /** - * try not match the columns of each row to a color which did not have - * those columns yet - */ - size_t c_used = 0; - for (size_t i = 0; i < sparsity.size(); i++) { - const std::set& row = sparsity[i]; - if (row.size() == 0) { - continue; //nothing to do - } - - // consider only the columns present in the sparsity pattern - std::set rowReduced; - if (_custom_hess.defined) { - for (size_t j : row) { - if (columns.find(j) != columns.end()) - rowReduced.insert(j); - } - } else { - rowReduced = row; - } - - bool newColor = true; - size_t colori; - for (size_t c = 0; c < c_used; c++) { - std::set& forbidden_c = colors[c].forbiddenRows; - if (!intersects(forbidden_c, rowReduced)) { - // no intersection - colori = c; - newColor = false; - forbidden_c.insert(rowReduced.begin(), rowReduced.end()); - break; - } - } - - if (newColor) { - colori = c_used; - colors[c_used].forbiddenRows = rowReduced; - c_used++; - } - - colors[colori].rows.insert(i); - - for (size_t j : rowReduced) { - colors[colori].column2Row[j] = i; - colors[colori].row2Columns[i].insert(j); - } - } - - colors.resize(c_used); //reduce size - return colors; -} - -template -void ModelCSourceGen::generateGlobalDirectionalFunctionSource(const std::string& function, - const std::string& suffix, - const std::string& function_sparsity, - const std::map >& elements) { - /** - * The function that matches each equation to a directional derivative function - */ - LanguageC langC(_baseTypeName); - std::string argsDcl = langC.generateDefaultFunctionArgumentsDcl(); - std::string args = langC.generateDefaultFunctionArguments(); - - _cache.str(""); - _cache << _name << "_" << function; - std::string model_function = _cache.str(); - _cache.str(""); - - _cache << LanguageC::ATOMICFUN_STRUCT_DEFINITION << "\n\n"; - generateFunctionDeclarationSource(_cache, model_function, suffix, elements, argsDcl); - _cache << "\n"; - _cache << "int " << model_function << "(" - "unsigned long pos, " << argsDcl << ") {\n" - " switch(pos) {\n"; - for (const auto& it : elements) { - // the size of each sparsity row - _cache << " case " << it.first << ":\n" - " " << model_function << "_" << suffix << it.first << "(" << args << ");\n" - " return 0; // done\n"; - } - _cache << " default:\n" - " return 1; // error\n" - " };\n"; - - _cache << "}\n"; - _sources[model_function + ".c"] = _cache.str(); - _cache.str(""); - - /** - * Sparsity - */ - generateSparsity1DSource2(_name + "_" + function_sparsity, elements); - _sources[_name + "_" + function_sparsity + ".c"] = _cache.str(); - _cache.str(""); -} - -template -template -void ModelCSourceGen::generateFunctionDeclarationSource(std::ostringstream& cache, - const std::string& model_function, - const std::string& suffix, - const std::map& elements, - const std::string& argsDcl) { - for (const auto& it : elements) { - size_t pos = it.first; - cache << "void " << model_function << "_" << suffix << pos << "(" << argsDcl << ");\n"; - } -} - -template -void ModelCSourceGen::generateSparsity1DSource(const std::string& function, - const std::vector& sparsity) { - _cache << "void " << function << "(" - "unsigned long const** sparsity," - " unsigned long* nnz) {\n"; - - // the size of each sparsity row - _cache << " "; - LanguageC::printStaticIndexArray(_cache, "nonzeros", sparsity); - - _cache << " *sparsity = nonzeros;\n" - " *nnz = " << sparsity.size() << ";\n" - "}\n"; -} - -template -void ModelCSourceGen::generateSparsity2DSource(const std::string& function, - const LocalSparsityInfo& sparsity) { - const std::vector& rows = sparsity.rows; - const std::vector& cols = sparsity.cols; - - CPPADCG_ASSERT_UNKNOWN(rows.size() == cols.size()); - - _cache << "void " << function << "(" - "unsigned long const** row," - " unsigned long const** col," - " unsigned long* nnz) {\n"; - - // the size of each sparsity row - _cache << " "; - LanguageC::printStaticIndexArray(_cache, "rows", rows); - - _cache << " "; - LanguageC::printStaticIndexArray(_cache, "cols", cols); - - _cache << " *row = rows;\n" - " *col = cols;\n" - " *nnz = " << rows.size() << ";\n" - "}\n"; -} - -template -void ModelCSourceGen::generateSparsity2DSource2(const std::string& function, - const std::vector& sparsities) { - _cache << "void " << function << "(" - "unsigned long i," - "unsigned long const** row," - " unsigned long const** col," - " unsigned long* nnz) {\n"; - - std::ostringstream os; - - for (size_t i = 0; i < sparsities.size(); i++) { - const std::vector& rows = sparsities[i].rows; - const std::vector& cols = sparsities[i].cols; - CPPADCG_ASSERT_UNKNOWN(rows.size() == cols.size()); - if (!rows.empty()) { - os.str(""); - os << "rows" << i; - _cache << " "; - LanguageC::printStaticIndexArray(_cache, os.str(), rows); - - os.str(""); - os << "cols" << i; - _cache << " "; - LanguageC::printStaticIndexArray(_cache, os.str(), cols); - } - } - - _cache << " switch(i) {\n"; - for (size_t i = 0; i < sparsities.size(); i++) { - // the size of each sparsity - if (!sparsities[i].rows.empty()) { - _cache << " case " << i << ":\n" - " *row = rows" << i << ";\n" - " *col = cols" << i << ";\n" - " *nnz = " << sparsities[i].rows.size() << ";\n" - " break;\n"; - } - } - - _cache << " default:\n" - " *row = 0;\n" - " *col = 0;\n" - " *nnz = 0;\n" - " break;\n" - " };\n" - "}\n"; -} - -template -void ModelCSourceGen::generateSparsity1DSource2(const std::string& function, - const std::map >& elements) { - - _cache << "void " << function << "(" - "unsigned long pos," - " unsigned long const** elements," - " unsigned long* nnz) {\n"; - - for (const auto& it : elements) { - // the size of each sparsity row - const std::vector& els = it.second; - _cache << " "; - std::ostringstream os; - os << "elements" << it.first; - LanguageC::printStaticIndexArray(_cache, os.str(), els); - } - - _cache << " switch(pos) {\n"; - for (const auto& it : elements) { - // the size of each sparsity row - _cache << " case " << it.first << ":\n" - " *elements = elements" << it.first << ";\n" - " *nnz = " << it.second.size() << ";\n" - " break;\n"; - } - _cache << " default:\n" - " *elements = 0;\n" - " *nnz = 0;\n" - " break;\n" - " };\n" - "}\n"; -} - -template -inline std::map > > ModelCSourceGen::determineOrderByCol(const std::map >& elements, - const LocalSparsityInfo& sparsity) { - return determineOrderByCol(elements, sparsity.rows, sparsity.cols); -} - -template -inline std::map > > ModelCSourceGen::determineOrderByCol(const std::map >& elements, - const std::vector& userRows, - const std::vector& userCols) { - std::map > > userLocation; - - for (const auto& it : elements) { - size_t col = it.first; - const std::vector& colElements = it.second; - - userLocation[col] = determineOrderByCol(col, colElements, userRows, userCols); - } - - return userLocation; -} - -template -inline std::vector > ModelCSourceGen::determineOrderByCol(size_t col, - const std::vector& colElements, - const std::vector& userRows, - const std::vector& userCols) { - std::vector > userLocationCol(colElements.size()); - - for (size_t er = 0; er < colElements.size(); er++) { - size_t row = colElements[er]; - for (size_t e = 0; e < userRows.size(); e++) { - if (userRows[e] == row && userCols[e] == col) { - userLocationCol[er].insert(e); - break; - } - } - } - - return userLocationCol; -} - -template -inline std::map > > ModelCSourceGen::determineOrderByRow(const std::map >& elements, - const LocalSparsityInfo& sparsity) { - return determineOrderByRow(elements, sparsity.rows, sparsity.cols); -} - -template -inline std::map > > ModelCSourceGen::determineOrderByRow(const std::map >& elements, - const std::vector& userRows, - const std::vector& userCols) { - std::map > > userLocation; - - for (const auto& it : elements) { - size_t row = it.first; - const std::vector& rowsElements = it.second; - userLocation[row] = determineOrderByRow(row, rowsElements, userRows, userCols); - } - - return userLocation; -} - -template -inline std::vector > ModelCSourceGen::determineOrderByRow(size_t row, - const std::vector& rowElements, - const std::vector& userRows, - const std::vector& userCols) { - std::vector > userLocationRow(rowElements.size()); - - for (size_t ec = 0; ec < rowElements.size(); ec++) { - size_t col = rowElements[ec]; - for (size_t e = 0; e < userRows.size(); e++) { - if (userCols[e] == col && userRows[e] == row) { - userLocationRow[ec].insert(e); - break; - } - } - } - - return userLocationRow; -} - -template -void ModelCSourceGen::printFileStartPThreads(std::ostringstream& cache, - const std::string& baseTypeName) { - cache << "\n"; - cache << CPPADCG_PTHREAD_POOL_H_FILE << "\n"; - cache << "\n"; - cache << "typedef struct ExecArgStruct {\n" - " cppadcg_function_type func;\n" - " " << baseTypeName + " const *const * in;\n" - " " << baseTypeName + "* out[1];\n" - " struct LangCAtomicFun atomicFun;\n" - "} ExecArgStruct;\n" - "\n" - "static void exec_func(void* arg) {\n" - " ExecArgStruct* eArg = (ExecArgStruct*) arg;\n" - " (*eArg->func)(eArg->in, eArg->out, eArg->atomicFun);\n" - "}\n"; -} - -template -void ModelCSourceGen::printFunctionStartPThreads(std::ostringstream& cache, - size_t size) { - auto repeatFill = [&](const std::string& txt){ - cache << "{"; - for (size_t i = 0; i < size; ++i) { - if (i != 0) cache << ", "; - cache << txt; - } - cache << "};"; - }; - - cache << " ExecArgStruct* args[" << size << "];\n"; - cache << " static cppadcg_thpool_function_type execute_functions[" << size << "] = "; - repeatFill("exec_func"); - cache << "\n"; - cache << " static float ref_elapsed[" << size << "] = "; - repeatFill("0"); - cache << "\n"; - cache << " static float elapsed[" << size << "] = "; - repeatFill("0"); - cache << "\n" - " static int order[" << size << "] = {"; - for (size_t i = 0; i < size; ++i) { - if (i != 0) cache << ", "; - cache << i; - } - cache << "};\n" - " static int job2Thread[" << size << "] = "; - repeatFill("-1"); - cache << "\n" - " static int last_elapsed_changed = 1;\n" - " unsigned int nBench = cppadcg_thpool_get_n_time_meas();\n" - " static unsigned int n_meas = 0;\n" - " int do_benchmark = " << (size > 0 ? "(n_meas < nBench && !cppadcg_thpool_is_disabled())" : "0") << ";\n" - " float* elapsed_p = do_benchmark ? elapsed : NULL;\n"; -} - -template -void ModelCSourceGen::printFunctionEndPThreads(std::ostringstream& cache, - size_t size) { - cache << " cppadcg_thpool_add_jobs(execute_functions, (void**) args, ref_elapsed, elapsed_p, order, job2Thread, " << size << ", last_elapsed_changed" << ");\n" - "\n" - " cppadcg_thpool_wait();\n" - "\n" - " for(i = 0; i < " << size << "; ++i) {\n" - " free(args[i]);\n" - " }\n" - "\n" - " if(do_benchmark) {\n" - " cppadcg_thpool_update_order(ref_elapsed, n_meas, elapsed, order, " << size << ");\n" - " n_meas++;\n" - " } else {\n" - " last_elapsed_changed = 0;\n" - " }\n"; -} - -template -void ModelCSourceGen::printFileStartOpenMP(std::ostringstream& cache) { - cache << CPPADCG_OPENMP_H_FILE << "\n" - "#include \n" - "#include \n" - "#include \n"; -} - -template -void ModelCSourceGen::printFunctionStartOpenMP(std::ostringstream& cache, - size_t size) { - cache << "\n" - " enum omp_sched_t old_kind;\n" - " int old_modifier;\n" - " int enabled = !cppadcg_openmp_is_disabled();\n" - " int verbose = cppadcg_openmp_is_verbose();\n" - " struct timespec start[" << size << "];\n" - " struct timespec end[" << size << "];\n" - " int thread_id[" << size << "];\n" - " unsigned int n_threads = cppadcg_openmp_get_threads();\n" - " if(n_threads > " << size << ")\n" - " n_threads = " << size << ";\n" - "\n" - " if(enabled) {\n" - " omp_get_schedule(&old_kind, &old_modifier);\n" - " cppadcg_openmp_apply_scheduler_strategy();\n" - " }\n"; -} - -template -void ModelCSourceGen::printLoopStartOpenMP(std::ostringstream& cache, - size_t size) { - cache <<"#pragma omp parallel for private(outLocal) schedule(runtime) if(enabled) num_threads(n_threads)\n" - " for(i = 0; i < " << size << "; ++i) {\n" - " int info;\n" - " if(verbose) {\n" - " thread_id[i] = omp_get_thread_num();\n" - " info = clock_gettime(CLOCK_MONOTONIC, &start[i]);\n" - " if(info != 0) {\n" - " start[i].tv_sec = 0;\n" - " start[i].tv_nsec = 0;\n" - " end[i].tv_sec = 0;\n" - " end[i].tv_nsec = 0;\n" - " }\n" - " }\n" - "\n"; -} - -template -void ModelCSourceGen::printLoopEndOpenMP(std::ostringstream& cache, - size_t size) { - cache <<"\n" - " if(verbose) {\n" - " if(info == 0) {\n" - " info = clock_gettime(CLOCK_MONOTONIC, &end[i]);\n" - " if(info != 0) {\n" - " end[i].tv_sec = 0;\n" - " end[i].tv_nsec = 0;\n" - " }\n" - " }\n" - " }\n" - " }\n" - "\n" - " if(enabled) {\n" - " omp_set_schedule(old_kind, old_modifier);\n" - " }\n" - "\n" - " if(verbose) {\n" - " struct timespec diff;\n" - " for (i = 0; i < " << size << "; ++i) {\n" - " if ((end[i].tv_nsec - start[i].tv_nsec) < 0) {\n" - " diff.tv_sec = end[i].tv_sec - start[i].tv_sec - 1;\n" - " diff.tv_nsec = end[i].tv_nsec - start[i].tv_nsec + 1000000000;\n" - " } else {\n" - " diff.tv_sec = end[i].tv_sec - start[i].tv_sec;\n" - " diff.tv_nsec = end[i].tv_nsec - start[i].tv_nsec;\n" - " }\n" - " fprintf(stdout, \"## Thread %i, Job %li, started at %ld.%.9ld, ended at %ld.%.9ld, elapsed %ld.%.9ld\\n\",\n" - " thread_id[i], i, start[i].tv_sec, start[i].tv_nsec, end[i].tv_sec, end[i].tv_nsec, diff.tv_sec, diff.tv_nsec);\n" - " }\n" - " }\n"; - -} - -template -void ModelCSourceGen::startingJob(const std::string& jobName, - const JobType& type) { - if (_jobTimer != nullptr) - _jobTimer->startingJob(jobName, type); -} - -template -inline void ModelCSourceGen::finishedJob() { - if (_jobTimer != nullptr) - _jobTimer->finishedJob(); -} - -/** - * - * Specializations - */ -template<> -inline std::string ModelCSourceGen::baseTypeName() { - return "double"; -} - -template<> -inline std::string ModelCSourceGen::baseTypeName() { - return "float"; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_jac.hpp b/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_jac.hpp deleted file mode 100644 index f67dbfd93..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_jac.hpp +++ /dev/null @@ -1,485 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_JAC_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_JAC_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -void ModelCSourceGen::generateJacobianSource() { - using std::vector; - - const std::string jobName = "Jacobian"; - - startingJob("'" + jobName + "'", JobTimer::GRAPH); - - CodeHandler handler; - handler.setJobTimer(_jobTimer); - - vector indVars(_fun.Domain()); - handler.makeVariables(indVars); - if (_x.size() > 0) { - for (size_t i = 0; i < indVars.size(); i++) { - indVars[i].setValue(_x[i]); - } - } - - size_t m = _fun.Range(); - size_t n = _fun.Domain(); - - vector jac(n * m); - if (_jacMode == JacobianADMode::Automatic) { - jac = _fun.Jacobian(indVars); - } else if (_jacMode == JacobianADMode::Forward) { - JacobianFor(_fun, indVars, jac); - } else { - JacobianRev(_fun, indVars, jac); - } - - finishedJob(); - - LanguageC langC(_baseTypeName); - langC.setMaxAssigmentsPerFunction(_maxAssignPerFunc, &_sources); - langC.setParameterPrecision(_parameterPrecision); - langC.setGenerateFunction(_name + "_" + FUNCTION_JACOBIAN); - - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("jac")); - - handler.generateCode(code, langC, jac, *nameGen, _atomicFunctions, jobName); -} - -template -void ModelCSourceGen::generateSparseJacobianSource(MultiThreadingType multiThreadingType) { - size_t m = _fun.Range(); - size_t n = _fun.Domain(); - - /** - * Determine the sparsity pattern - */ - determineJacobianSparsity(); - - bool forwardMode; - - if (_jacMode == JacobianADMode::Automatic) { - if (_custom_jac.defined) { - forwardMode = estimateBestJacobianADMode(_jacSparsity.rows, _jacSparsity.cols); - } else { - forwardMode = n <= m; - } - } else { - forwardMode = _jacMode == JacobianADMode::Forward; - } - - /** - * call the appropriate method for source code generation - */ - if (_sparseJacobianReusesOne && _forwardOne && forwardMode) { - generateSparseJacobianForRevSource(true, multiThreadingType); - } else if (_sparseJacobianReusesOne && _reverseOne && !forwardMode) { - generateSparseJacobianForRevSource(false, multiThreadingType); - } else { - generateSparseJacobianSource(forwardMode); - } -} - -template -void ModelCSourceGen::generateSparseJacobianSource(bool forward) { - using std::vector; - - const std::string jobName = "sparse Jacobian"; - - //size_t m = _fun.Range(); - size_t n = _fun.Domain(); - - startingJob("'" + jobName + "'", JobTimer::GRAPH); - - CodeHandler handler; - handler.setJobTimer(_jobTimer); - - vector indVars(n); - handler.makeVariables(indVars); - if (_x.size() > 0) { - for (size_t i = 0; i < n; i++) { - indVars[i].setValue(_x[i]); - } - } - - vector jac(_jacSparsity.rows.size()); - if (_loopTapes.empty()) { - //printSparsityPattern(_jacSparsity.sparsity, "jac sparsity"); - CppAD::sparse_jacobian_work work; - if (forward) { - _fun.SparseJacobianForward(indVars, _jacSparsity.sparsity, _jacSparsity.rows, _jacSparsity.cols, jac, work); - } else { - _fun.SparseJacobianReverse(indVars, _jacSparsity.sparsity, _jacSparsity.rows, _jacSparsity.cols, jac, work); - } - - } else { - jac = prepareSparseJacobianWithLoops(handler, indVars, forward); - } - - finishedJob(); - - LanguageC langC(_baseTypeName); - langC.setMaxAssigmentsPerFunction(_maxAssignPerFunc, &_sources); - langC.setParameterPrecision(_parameterPrecision); - langC.setGenerateFunction(_name + "_" + FUNCTION_SPARSE_JACOBIAN); - - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("jac")); - - handler.generateCode(code, langC, jac, *nameGen, _atomicFunctions, jobName); -} - -template -void ModelCSourceGen::generateSparseJacobianForRevSource(bool forward, - MultiThreadingType multiThreadingType) { - //size_t m = _fun.Range(); - //size_t n = _fun.Domain(); - using namespace std; - - std::map jacInfo; - string functionRevFor, revForSuffix; - if (forward) { - // jacInfo[var].index{equations} - for (size_t e = 0; e < _jacSparsity.rows.size(); e++) { - jacInfo[_jacSparsity.cols[e]].indexes.push_back(_jacSparsity.rows[e]); - } - for (auto& it : jacInfo) { - size_t col = it.first; - it.second.locations = determineOrderByCol(col, it.second.indexes, _jacSparsity.rows, _jacSparsity.cols); - } - _cache.str(""); - _cache << _name << "_" << FUNCTION_SPARSE_FORWARD_ONE; - functionRevFor = _cache.str(); - revForSuffix = "indep"; - } else { - // jacInfo[equation].index{vars} - for (size_t e = 0; e < _jacSparsity.rows.size(); e++) { - jacInfo[_jacSparsity.rows[e]].indexes.push_back(_jacSparsity.cols[e]); - } - for (auto& it : jacInfo) { - size_t row = it.first; - it.second.locations = determineOrderByRow(row, it.second.indexes, _jacSparsity.rows, _jacSparsity.cols); - } - _cache.str(""); - _cache << _name << "_" << FUNCTION_SPARSE_REVERSE_ONE; - functionRevFor = _cache.str(); - revForSuffix = "dep"; - } - - - /** - * determine to which functions we can provide the jacobian row/column - * directly without needing a temporary array (compressed) - */ - for (auto& it : jacInfo) { - const std::vector& els = it.second.indexes; - const std::vector >& location = it.second.locations; - CPPADCG_ASSERT_UNKNOWN(els.size() == location.size()); - CPPADCG_ASSERT_UNKNOWN(els.size() > 0); - - bool passed = true; - size_t jacArrayStart = *location[0].begin(); - for (size_t e = 0; e < els.size(); e++) { - if (location[e].size() > 1) { - passed = false; // too many elements - break; - } - if (*location[e].begin() != jacArrayStart + e) { - passed = false; // wrong order - break; - } - } - it.second.ordered = passed; - } - - size_t maxCompressedSize = 0; - map::const_iterator itOrd; - map >::const_iterator it; - for (const auto& it : jacInfo) { - if (it.second.indexes.size() > maxCompressedSize && !it.second.ordered) - maxCompressedSize = it.second.indexes.size(); - } - - if (!_loopTapes.empty()) { - /** - * with loops - */ - if (forward) { - generateSparseJacobianWithLoopsSourceFromForRev(jacInfo, maxCompressedSize, - FUNCTION_SPARSE_FORWARD_ONE, "indep", "jcol", - _nonLoopFor1Elements, _loopFor1Groups, - generateFunctionNameLoopFor1); - } else { - generateSparseJacobianWithLoopsSourceFromForRev(jacInfo, maxCompressedSize, - FUNCTION_SPARSE_REVERSE_ONE, "dep", "jrow", - _nonLoopRev1Elements, _loopRev1Groups, - generateFunctionNameLoopRev1); - } - return; - } - - _cache.str(""); - _cache << _name << "_" << FUNCTION_SPARSE_JACOBIAN; - string functionName(_cache.str()); - - if(!_multiThreading || multiThreadingType == MultiThreadingType::NONE) { - _sources[functionName + ".c"] = generateSparseJacobianForRevSingleThreadSource(functionName, jacInfo, maxCompressedSize, functionRevFor, revForSuffix, forward); - } else { - _sources[functionName + ".c"] = generateSparseJacobianForRevMultiThreadSource(functionName, jacInfo, maxCompressedSize, functionRevFor, revForSuffix, forward, multiThreadingType); - } - - _cache.str(""); -} - -template -std::string ModelCSourceGen::generateSparseJacobianForRevSingleThreadSource(const std::string& functionName, - std::map jacInfo, - size_t maxCompressedSize, - const std::string& functionRevFor, - const std::string& revForSuffix, - bool forward) { - - LanguageC langC(_baseTypeName); - std::string argsDcl = langC.generateDefaultFunctionArgumentsDcl(); - - _cache.str(""); - _cache << "#include \n" - "\n" - << LanguageC::ATOMICFUN_STRUCT_DEFINITION << "\n\n"; - generateFunctionDeclarationSource(_cache, functionRevFor, revForSuffix, jacInfo, argsDcl); - _cache << "\n" - "void " << functionName << "(" << argsDcl << ") {\n" - " " << _baseTypeName << " const * inLocal[2];\n" - " " << _baseTypeName << " inLocal1 = 1;\n" - " " << _baseTypeName << " * outLocal[1];\n" - " " << _baseTypeName << " compressed[" << maxCompressedSize << "];\n" - " " << _baseTypeName << " * jac = out[0];\n" - "\n" - " inLocal[0] = in[0];\n" - " inLocal[1] = &inLocal1;\n" - " outLocal[0] = compressed;\n"; - - langC.setArgumentIn("inLocal"); - langC.setArgumentOut("outLocal"); - std::string argsLocal = langC.generateDefaultFunctionArguments(); - - bool previousCompressed = true; - for (const auto& it : jacInfo) { - size_t index = it.first; - const std::vector& els = it.second.indexes; - const std::vector >& location = it.second.locations; - CPPADCG_ASSERT_UNKNOWN(els.size() == location.size()); - - _cache << "\n"; - bool compressed = !it.second.ordered; - if (!compressed) { - _cache << " outLocal[0] = &jac[" << *location[0].begin() << "];\n"; - } else if (!previousCompressed) { - _cache << " outLocal[0] = compressed;\n"; - } - _cache << " " << functionRevFor << "_" << revForSuffix << index << "(" << argsLocal << ");\n"; - if (compressed) { - for (size_t e = 0; e < els.size(); e++) { - _cache << " "; - for (size_t itl : location[e]) { - _cache << "jac[" << (itl) << "] = "; - } - _cache << "compressed[" << e << "];\n"; - } - } - previousCompressed = compressed; - } - - _cache << "\n" - "}\n"; - - return _cache.str(); -} - -template -std::string ModelCSourceGen::generateSparseJacobianForRevMultiThreadSource(const std::string& functionName, - std::map jacInfo, - size_t maxCompressedSize, - const std::string& functionRevFor, - const std::string& revForSuffix, - bool forward, - MultiThreadingType multiThreadingType) { - LanguageC langC(_baseTypeName); - std::string argsDcl = langC.generateDefaultFunctionArgumentsDcl(); - - _cache.str(""); - _cache << "#include \n" - "\n" - << LanguageC::ATOMICFUN_STRUCT_DEFINITION << "\n\n"; - generateFunctionDeclarationSource(_cache, functionRevFor, revForSuffix, jacInfo, argsDcl); - - langC.setArgumentIn("inLocal"); - langC.setArgumentOut("outLocal"); - std::string argsLocal = langC.generateDefaultFunctionArguments(); - - /** - * Create independent functions for each row/column of the Jacobian - */ - for (const auto& it : jacInfo) { - size_t index = it.first; - const std::vector& els = it.second.indexes; - const std::vector >& location = it.second.locations; - CPPADCG_ASSERT_UNKNOWN(els.size() == location.size()); - - bool compressed = !it.second.ordered; - if (!compressed) { - continue; - } - - _cache << "void " << functionRevFor << "_" << revForSuffix << index << "_wrap(" << argsDcl << ") {\n" - " " << _baseTypeName << " const * inLocal[2];\n" - " " << _baseTypeName << " inLocal1 = 1;\n" - " " << _baseTypeName << " * outLocal[1];\n" - " " << _baseTypeName << " compressed[" << it.second.indexes.size() << "];\n" - " " << _baseTypeName << " * jac = out[0];\n" - "\n" - " inLocal[0] = in[0];\n" - " inLocal[1] = &inLocal1;\n" - " outLocal[0] = compressed;\n"; - - _cache << " " << functionRevFor << "_" << revForSuffix << index << "(" << argsLocal << ");\n"; - for (size_t e = 0; e < els.size(); e++) { - _cache << " "; - for (size_t itl : location[e]) { - _cache << "jac[" << (itl) << "] = "; - } - _cache << "compressed[" << e << "];\n"; - } - _cache << "}\n"; - } - - _cache << "\n" - "typedef void (*cppadcg_function_type) (" << argsDcl << ");\n"; - - /** - * PThreads pool needs a function with a void pointer argument - */ - if(multiThreadingType == MultiThreadingType::OPENMP) { - _cache << "\n"; - printFileStartOpenMP(_cache); - _cache << "\n"; - - } else { - assert(multiThreadingType == MultiThreadingType::PTHREADS); - - printFileStartPThreads(_cache, _baseTypeName); - } - - /** - * Jacobian function - */ - _cache << "\n" - "void " << functionName << "(" << argsDcl << ") {\n" - " static const cppadcg_function_type p[" << jacInfo.size() << "] = {"; - for (const auto& it : jacInfo) { - size_t index = it.first; - if (index != jacInfo.begin()->first) _cache << ", "; - if (it.second.ordered) { - _cache << functionRevFor << "_" << revForSuffix << index; - } else { - _cache << functionRevFor << "_" << revForSuffix << index << "_wrap"; - } - } - _cache << "};\n" - " static const long offset["<< jacInfo.size() <<"] = {"; - for (const auto& it : jacInfo) { - if (it.first != jacInfo.begin()->first) _cache << ", "; - if (it.second.ordered) { - _cache << *it.second.locations[0].begin(); - } else { - _cache << "0"; - } - } - _cache << "};\n" - " " << _baseTypeName << " inLocal1 = 1;\n" - " " << _baseTypeName << " const * inLocal[2] = {in[0], &inLocal1};\n" - " " << _baseTypeName << " * outLocal[1];\n" - " " << _baseTypeName << " * jac = out[0];\n" - " long i;\n" - "\n"; - - if(multiThreadingType == MultiThreadingType::OPENMP) { - printFunctionStartOpenMP(_cache, jacInfo.size()); - _cache << "\n"; - printLoopStartOpenMP(_cache, jacInfo.size()); - _cache << " outLocal[0] = &jac[offset[i]];\n" - " (*p[i])(" << argsLocal << ");\n"; - printLoopEndOpenMP(_cache, jacInfo.size()); - _cache << "\n"; - - } else { - assert(multiThreadingType == MultiThreadingType::PTHREADS); - - printFunctionStartPThreads(_cache, jacInfo.size()); - _cache << "\n" - " for(i = 0; i < " << jacInfo.size() << "; ++i) {\n" - " args[i] = (ExecArgStruct*) malloc(sizeof(ExecArgStruct));\n" - " args[i]->func = p[i];\n" - " args[i]->in = inLocal;\n" - " args[i]->out[0] = &jac[offset[i]];\n" - " args[i]->atomicFun = " << langC.getArgumentAtomic() << ";\n" - " }\n" - "\n"; - printFunctionEndPThreads(_cache, jacInfo.size()); - } - - _cache << "\n" - "}\n"; - - return _cache.str(); -} - -template -void ModelCSourceGen::determineJacobianSparsity() { - if (_jacSparsity.sparsity.size() > 0) { - return; - } - - /** - * Determine the sparsity pattern - */ - _jacSparsity.sparsity = jacobianSparsitySet (_fun); - - if (!_custom_jac.defined) { - generateSparsityIndexes(_jacSparsity.sparsity, _jacSparsity.rows, _jacSparsity.cols); - - } else { - _jacSparsity.rows = _custom_jac.row; - _jacSparsity.cols = _custom_jac.col; - } -} - -template -void ModelCSourceGen::generateJacobianSparsitySource() { - determineJacobianSparsity(); - - generateSparsity2DSource(_name + "_" + FUNCTION_JACOBIAN_SPARSITY, _jacSparsity); - _sources[_name + "_" + FUNCTION_JACOBIAN_SPARSITY + ".c"] = _cache.str(); - _cache.str(""); -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_rev1.hpp b/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_rev1.hpp deleted file mode 100644 index d3abf29ed..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_rev1.hpp +++ /dev/null @@ -1,311 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_REV1_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_REV1_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -void ModelCSourceGen::generateSparseReverseOneSources() { - - determineJacobianSparsity(); - - // elements[equation]{vars} - std::map > elements; - for (size_t e = 0; e < _jacSparsity.rows.size(); e++) { - elements[_jacSparsity.rows[e]].push_back(_jacSparsity.cols[e]); - } - - if (!_loopTapes.empty()) { - /** - * with loops - */ - prepareSparseReverseOneWithLoops(elements); - return; - } - - /** - * Generate one function for each dependent variable - */ - startingJob("'model (reverse one)'", JobTimer::SOURCE_GENERATION); - - if (isAtomicsUsed()) { - generateSparseReverseOneSourcesWithAtomics(elements); - } else { - generateSparseReverseOneSourcesNoAtomics(elements); - } - - finishedJob(); - - _cache.str(""); - - generateGlobalDirectionalFunctionSource(FUNCTION_SPARSE_REVERSE_ONE, - "dep", - FUNCTION_REVERSE_ONE_SPARSITY, - elements); -} - -template -void ModelCSourceGen::generateSparseReverseOneSourcesWithAtomics(const std::map >& elements) { - using std::vector; - - /** - * Generate one function for each dependent variable - */ - size_t m = _fun.Range(); - size_t n = _fun.Domain(); - - vector w(m); - - /** - * Generate one function for each dependent variable - */ - const std::string jobName = "model (reverse one)"; - startingJob("'" + jobName + "'", JobTimer::SOURCE_GENERATION); - - for (const auto& it : elements) { - size_t i = it.first; - const std::vector& cols = it.second; - - _cache.str(""); - _cache << "model (reverse one, dep " << i << ")"; - const std::string subJobName = _cache.str(); - - startingJob("'" + subJobName + "'", JobTimer::GRAPH); - - CodeHandler handler; - handler.setJobTimer(_jobTimer); - - vector indVars(_fun.Domain()); - handler.makeVariables(indVars); - if (_x.size() > 0) { - for (size_t i = 0; i < n; i++) { - indVars[i].setValue(_x[i]); - } - } - - CGBase py; - handler.makeVariable(py); - if (_x.size() > 0) { - py.setValue(Base(1.0)); - } - - // TODO: consider caching the zero order coefficients somehow between calls - _fun.Forward(0, indVars); - - w[i] = py; - vector dw = _fun.Reverse(1, w); - CPPADCG_ASSERT_UNKNOWN(dw.size() == n); - w[i] = Base(0); - - vector dwCustom; - for (size_t it2 : cols) { - dwCustom.push_back(dw[it2]); - } - - finishedJob(); - - LanguageC langC(_baseTypeName); - langC.setMaxAssigmentsPerFunction(_maxAssignPerFunc, &_sources); - langC.setParameterPrecision(_parameterPrecision); - _cache.str(""); - _cache << _name << "_" << FUNCTION_SPARSE_REVERSE_ONE << "_dep" << i; - langC.setGenerateFunction(_cache.str()); - - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("dw")); - LangCDefaultHessianVarNameGenerator nameGenHess(nameGen.get(), "py", n); - - handler.generateCode(code, langC, dwCustom, nameGenHess, _atomicFunctions, subJobName); - } -} - -template -void ModelCSourceGen::generateSparseReverseOneSourcesNoAtomics(const std::map >& elements) { - using std::vector; - - /** - * Jacobian - */ - size_t m = _fun.Range(); - size_t n = _fun.Domain(); - - CodeHandler handler; - handler.setJobTimer(_jobTimer); - - vector x(n); - handler.makeVariables(x); - if (_x.size() > 0) { - for (size_t i = 0; i < n; i++) { - x[i].setValue(_x[i]); - } - } - - CGBase py; - handler.makeVariable(py); - if (_x.size() > 0) { - py.setValue(Base(1.0)); - } - - vector jacFlat(_jacSparsity.rows.size()); - - CppAD::sparse_jacobian_work work; // temporary structure for CPPAD - _fun.SparseJacobianReverse(x, _jacSparsity.sparsity, _jacSparsity.rows, _jacSparsity.cols, jacFlat, work); - - /** - * organize results - */ - std::map > jac; // by row - std::vector > positions(m); // by row - - for (const auto& it : elements) { - size_t i = it.first; - const std::vector& row = it.second; - - jac[i].resize(row.size()); - std::map& pos = positions[i]; - - for (size_t e = 0; e < row.size(); e++) { - size_t j = row[e]; - pos[j] = e; - } - } - - for (size_t el = 0; el < _jacSparsity.rows.size(); el++) { - size_t i = _jacSparsity.rows[el]; - size_t j = _jacSparsity.cols[el]; - size_t e = positions[i].at(j); - - vector& row = jac[i]; - row[e] = jacFlat[el] * py; - } - - /** - * Create source for each equation/row - */ - typename std::map >::iterator itI; - for (itI = jac.begin(); itI != jac.end(); ++itI) { - size_t i = itI->first; - vector& dwCustom = itI->second; - - _cache.str(""); - _cache << "model (reverse one, dep " << i << ")"; - const std::string subJobName = _cache.str(); - - LanguageC langC(_baseTypeName); - langC.setMaxAssigmentsPerFunction(_maxAssignPerFunc, &_sources); - langC.setParameterPrecision(_parameterPrecision); - _cache.str(""); - _cache << _name << "_" << FUNCTION_SPARSE_REVERSE_ONE << "_dep" << i; - langC.setGenerateFunction(_cache.str()); - - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("dw")); - LangCDefaultHessianVarNameGenerator nameGenHess(nameGen.get(), "py", n); - - handler.generateCode(code, langC, dwCustom, nameGenHess, _atomicFunctions, subJobName); - } -} - -template -void ModelCSourceGen::generateReverseOneSources() { - size_t m = _fun.Range(); - size_t n = _fun.Domain(); - - _cache.str(""); - _cache << _name << "_" << FUNCTION_REVERSE_ONE; - std::string model_function(_cache.str()); - _cache.str(""); - - LanguageC langC(_baseTypeName); - std::string argsDcl = langC.generateDefaultFunctionArgumentsDcl(); - std::string args = langC.generateDefaultFunctionArguments(); - - _cache << "#include \n" - << LanguageC::ATOMICFUN_STRUCT_DEFINITION << "\n" - "\n" - "void " << _name << "_" << FUNCTION_SPARSE_REVERSE_ONE << "(unsigned long pos, " << argsDcl << ");\n" - "void " << _name << "_" << FUNCTION_REVERSE_ONE_SPARSITY << "(unsigned long pos, unsigned long const** elements, unsigned long* nnz);\n" - "\n" - "int " << model_function << "(" - << _baseTypeName << " const x[], " - << _baseTypeName << " const ty[]," - << _baseTypeName << " px[], " - << _baseTypeName << " const py[], " - << langC.generateArgumentAtomicDcl() << ") {\n" - " unsigned long ei, ePos, i, j, nnz, nnzMax;\n" - " unsigned long const* pos;\n" - " unsigned long* pyPos;\n" - " unsigned long nnzPy;\n" - " " << _baseTypeName << " const * in[2];\n" - " " << _baseTypeName << "* out[1];\n" - " " << _baseTypeName << "* compressed;\n" - "\n" - " pyPos = 0;\n" - " nnzPy = 0;\n" - " nnzMax = 0;\n" - " for (i = 0; i < " << m << "; i++) {\n" - " if (py[i] != 0.0) {\n" - " nnzPy++;\n" - " pyPos = (unsigned long*) realloc(pyPos, nnzPy * sizeof(unsigned long));\n" - " pyPos[nnzPy - 1] = i;\n" - " " << _name << "_" << FUNCTION_REVERSE_ONE_SPARSITY << "(i, &pos, &nnz);\n" - " if(nnz > nnzMax)\n" - " nnzMax = nnz;\n" - " }\n" - " }\n" - " for (j = 0; j < " << n << "; j++) {\n" - " px[j] = 0;\n" - " }\n" - "\n" - " if (nnzPy == 0) {\n" - " free(pyPos);\n" - " return 0; //nothing to do\n" - " }\n" - "\n" - " compressed = (" << _baseTypeName << "*) malloc(nnzMax * sizeof(" << _baseTypeName << "));\n" - "\n" - " for (ei = 0; ei < nnzPy; ei++) {\n" - " i = pyPos[ei];\n" - " " << _name << "_" << FUNCTION_REVERSE_ONE_SPARSITY << "(i, &pos, &nnz);\n" - "\n" - " in[0] = x;\n" - " in[1] = &py[i];\n" - " out[0] = compressed;\n"; - if (!_loopTapes.empty()) { - _cache << " for(ePos = 0; ePos < nnz; ePos++)\n" - " compressed[ePos] = 0;\n" - "\n"; - } - _cache << " " << _name << "_" << FUNCTION_SPARSE_REVERSE_ONE << "(i, " << args << ");\n" - "\n" - " for (ePos = 0; ePos < nnz; ePos++) {\n" - " px[pos[ePos]] += compressed[ePos];\n" - " }\n" - "\n" - " }\n" - " free(compressed);\n" - " free(pyPos);\n" - " return 0;\n" - "}\n"; - _sources[model_function + ".c"] = _cache.str(); - _cache.str(""); -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_rev2.hpp b/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_rev2.hpp deleted file mode 100644 index 7471817b9..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/model_c_source_gen_rev2.hpp +++ /dev/null @@ -1,355 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_REV2_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_REV2_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -void ModelCSourceGen::generateSparseReverseTwoSources() { - - determineHessianSparsity(); - - /** - * we might have to consider a slightly different order than the one - * specified by the user according to the available elements in the sparsity - */ - std::vector evalRows, evalCols; - determineSecondOrderElements4Eval(evalRows, evalCols); - - // elements[var]{vars} - std::map > elements; - for (size_t e = 0; e < evalCols.size(); e++) { - elements[evalRows[e]].push_back(evalCols[e]); - } - - if (!_loopTapes.empty()) { - /** - * with loops - */ - prepareSparseReverseTwoWithLoops(elements); - return; - } - - if (!evalRows.empty()) { - - startingJob("'model (reverse two)'", JobTimer::SOURCE_GENERATION); - - if (isAtomicsUsed()) { - generateSparseReverseTwoSourcesWithAtomics(elements); - } else { - generateSparseReverseTwoSourcesNoAtomics(elements, evalRows, evalCols); - } - - finishedJob(); - - _cache.str(""); - } - - generateGlobalDirectionalFunctionSource(FUNCTION_SPARSE_REVERSE_TWO, - "indep", - FUNCTION_REVERSE_TWO_SPARSITY, - elements); -} - -template -void ModelCSourceGen::generateSparseReverseTwoSourcesWithAtomics(const std::map >& elements) { - using std::vector; - - const size_t m = _fun.Range(); - const size_t n = _fun.Domain(); - //const size_t k = 1; - const size_t p = 2; - - vector tx1v(n); - - for (const auto& it : elements) { - size_t j = it.first; - const std::vector& cols = it.second; - - _cache.str(""); - _cache << "model (reverse two, indep " << j << ")"; - const std::string subJobName = _cache.str(); - - startingJob("'" + subJobName + "'", JobTimer::GRAPH); - - CodeHandler handler; - handler.setJobTimer(_jobTimer); - - vector tx0(n); - handler.makeVariables(tx0); - if (_x.size() > 0) { - for (size_t i = 0; i < n; i++) { - tx0[i].setValue(_x[i]); - } - } - - CGBase tx1; - handler.makeVariable(tx1); - if (_x.size() > 0) { - tx1.setValue(Base(1.0)); - } - - vector py(m); // (k+1)*m is not used because we are not interested in all values - handler.makeVariables(py); - if (_x.size() > 0) { - for (size_t i = 0; i < m; i++) { - py[i].setValue(Base(1.0)); - } - } - - _fun.Forward(0, tx0); - - tx1v[j] = tx1; - _fun.Forward(1, tx1v); - tx1v[j] = Base(0); - vector px = _fun.Reverse(2, py); - CPPADCG_ASSERT_UNKNOWN(px.size() == 2 * n); - - vector pxCustom; - for (size_t jj : cols) { - pxCustom.push_back(px[jj * p + 1]); // not interested in all values - } - - finishedJob(); - - LanguageC langC(_baseTypeName); - langC.setMaxAssigmentsPerFunction(_maxAssignPerFunc, &_sources); - langC.setParameterPrecision(_parameterPrecision); - _cache.str(""); - _cache << _name << "_" << FUNCTION_SPARSE_REVERSE_TWO << "_indep" << j; - langC.setGenerateFunction(_cache.str()); - - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("px")); - LangCDefaultReverse2VarNameGenerator nameGenRev2(nameGen.get(), n, 1); - - handler.generateCode(code, langC, pxCustom, nameGenRev2, _atomicFunctions, subJobName); - } -} - -template -void ModelCSourceGen::generateSparseReverseTwoSourcesNoAtomics(const std::map >& elements, - const std::vector& evalRows, - const std::vector& evalCols) { - using std::vector; - - const size_t m = _fun.Range(); - const size_t n = _fun.Domain(); - - // save compressed positions - std::map > positions; - for (const auto& itJ1 : elements) { - size_t j1 = itJ1.first; - const std::vector& row = itJ1.second; - std::map& pos = positions[j1]; - - for (size_t e = 0; e < row.size(); e++) { - size_t j2 = row[e]; - pos[j2] = e; - } - } - - // we can use a new handler to reduce memory usage - CodeHandler handler; - handler.setJobTimer(_jobTimer); - - vector tx0(n); - handler.makeVariables(tx0); - if (_x.size() > 0) { - for (size_t i = 0; i < n; i++) { - tx0[i].setValue(_x[i]); - } - } - - CGBase tx1; - handler.makeVariable(tx1); - if (_x.size() > 0) { - tx1.setValue(Base(1.0)); - } - - vector py(m); // (k+1)*m is not used because we are not interested in all values - handler.makeVariables(py); - if (_x.size() > 0) { - for (size_t i = 0; i < m; i++) { - py[i].setValue(Base(1.0)); - } - } - - vector hessFlat(evalRows.size()); - - CppAD::sparse_hessian_work work; // temporary structure for CPPAD - // "cppad.symmetric" may have missing values for functions using atomic - // functions which only provide half of the elements, but there is none here - work.color_method = "cppad.symmetric"; - _fun.SparseHessian(tx0, py, _hessSparsity.sparsity, evalRows, evalCols, hessFlat, work); - - std::map > hess; - for (const auto& itJ1 : elements) { - size_t j1 = itJ1.first; - hess[j1].resize(itJ1.second.size()); - } - - // organize hessian elements - for (size_t el = 0; el < evalRows.size(); el++) { - size_t j1 = evalRows[el]; - size_t j2 = evalCols[el]; - size_t e = positions[j1][j2]; - - hess[j1][e] = hessFlat[el]; - } - - /** - * Generate one function for each independent variable - */ - for (const auto& it : hess) { - size_t j = it.first; - const vector& row = it.second; - - _cache.str(""); - _cache << "model (reverse two, indep " << j << ")"; - const std::string subJobName = _cache.str(); - - vector pxCustom(row.size()); - for (size_t e = 0; e < row.size(); e++) { - pxCustom[e] = row[e] * tx1; - } - - LanguageC langC(_baseTypeName); - langC.setMaxAssigmentsPerFunction(_maxAssignPerFunc, &_sources); - langC.setParameterPrecision(_parameterPrecision); - _cache.str(""); - _cache << _name << "_" << FUNCTION_SPARSE_REVERSE_TWO << "_indep" << j; - langC.setGenerateFunction(_cache.str()); - - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("px")); - LangCDefaultReverse2VarNameGenerator nameGenRev2(nameGen.get(), n, 1); - - handler.generateCode(code, langC, pxCustom, nameGenRev2, _atomicFunctions, subJobName); - } -} - -template -void ModelCSourceGen::generateReverseTwoSources() { - size_t m = _fun.Range(); - size_t n = _fun.Domain(); - - _cache.str(""); - _cache << _name << "_" << FUNCTION_REVERSE_TWO; - std::string model_function(_cache.str()); - _cache.str(""); - - LanguageC langC(_baseTypeName); - std::string argsDcl = langC.generateDefaultFunctionArgumentsDcl(); - std::string args = langC.generateDefaultFunctionArguments(); - - _cache << "#include \n" - << LanguageC::ATOMICFUN_STRUCT_DEFINITION << "\n" - "\n" - "void " << _name << "_" << FUNCTION_SPARSE_REVERSE_TWO << "(unsigned long pos, " << argsDcl << ");\n" - "void " << _name << "_" << FUNCTION_REVERSE_TWO_SPARSITY << "(unsigned long pos, unsigned long const** elements, unsigned long* nnz);\n" - "\n" - "int " << model_function << "(" - << _baseTypeName << " const tx[], " - << _baseTypeName << " const ty[], " - << _baseTypeName << " px[], " - << _baseTypeName << " const py[], " - << langC.generateArgumentAtomicDcl() << ") {\n" - " unsigned long ej, ePos, i, j, nnz, nnzMax;\n" - " unsigned long const* pos;\n" - " unsigned long* txPos;\n" - " unsigned long nnzTx;\n" - " " << _baseTypeName << " const * in[3];\n" - " " << _baseTypeName << "* out[1];\n" - " " << _baseTypeName << " x[" << n << "];\n" - " " << _baseTypeName << " w[" << m << "];\n" - " " << _baseTypeName << "* compressed;\n" - " int nonZeroW;\n" - "\n" - " nonZeroW = 0;\n" - " for (i = 0; i < " << m << "; i++) {\n" - " if (py[i * 2] != 0.0) {\n" - " return 1; // error\n" - " }\n" - " w[i] = py[i * 2 + 1];\n" - " if(w[i] != 0.0) nonZeroW++;\n" - " }\n" - "\n" - " for (j = 0; j < " << n << "; j++) {\n" - " px[j * 2] = 0;\n" - " }\n" - "\n" - " if(nonZeroW == 0)\n" - " return 0; //nothing to do\n" - "\n" - " txPos = 0;\n" - " nnzTx = 0;\n" - " nnzMax = 0;\n" - " for (j = 0; j < " << n << "; j++) {\n" - " if (tx[j * 2 + 1] != 0.0) {\n" - " nnzTx++;\n" - " txPos = (unsigned long*) realloc(txPos, nnzTx * sizeof(unsigned long));\n" - " txPos[nnzTx - 1] = j;\n" - " " << _name << "_" << FUNCTION_REVERSE_TWO_SPARSITY << "(j, &pos, &nnz);\n" - " if(nnz > nnzMax)\n" - " nnzMax = nnz;\n" - " }\n" - " }\n" - "\n" - " if (nnzTx == 0) {\n" - " free(txPos);\n" - " return 0; //nothing to do\n" - " }\n" - "\n" - " for (j = 0; j < " << n << "; j++)\n" - " x[j] = tx[j * 2];\n" - "\n" - " compressed = (" << _baseTypeName << "*) malloc(nnzMax * sizeof(" << _baseTypeName << "));\n" - "\n" - " for (ej = 0; ej < nnzTx; ej++) {\n" - " j = txPos[ej];\n" - " " << _name << "_" << FUNCTION_REVERSE_TWO_SPARSITY << "(j, &pos, &nnz);\n" - "\n" - " in[0] = x;\n" - " in[1] = &tx[j * 2 + 1];\n" - " in[2] = w;\n" - " out[0] = compressed;\n"; - if (!_loopTapes.empty()) { - _cache << " for(ePos = 0; ePos < nnz; ePos++)\n" - " compressed[ePos] = 0;\n" - "\n"; - } - _cache << " " << _name << "_" << FUNCTION_SPARSE_REVERSE_TWO << "(j, " << args << ");\n" - "\n" - " for (ePos = 0; ePos < nnz; ePos++) {\n" - " px[pos[ePos] * 2] += compressed[ePos];\n" - " }\n" - "\n" - " }\n" - " free(compressed);\n" - " free(txPos);\n" - " return 0;\n" - "};\n"; - - _sources[model_function + ".c"] = _cache.str(); - _cache.str(""); -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/model_library.hpp b/ct_core/include/ct/external/cppad/cg/model/model_library.hpp deleted file mode 100644 index 4c0154519..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/model_library.hpp +++ /dev/null @@ -1,146 +0,0 @@ -#ifndef CPPAD_CG_MODEL_LIBRARY_INCLUDED -#define CPPAD_CG_MODEL_LIBRARY_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Abstract class used to load models - * - * @author Joao Leal - */ -template -class ModelLibrary { -public: - /** - * Provides the model names in the dynamic library. - * - * @return the model names - */ - virtual std::set getModelNames() = 0; - - /** - * Creates a new GenericModel object that can be used to evaluate the - * model. - * This object must be released by the user! - * - * @param modelName The model name. - * @return The model object (must be released by the user) or nullptr if - * no model exists with the provided name - */ - virtual GenericModel* model(const std::string& modelName) = 0; - - /** - * Defines whether or not to disable multithreaded model evaluations. - * This only works if the models if they were compiled with - * multithreading support. - * - * @param disabled true to only use the current thread to evaluate models. - */ - virtual void setThreadPoolDisabled(bool disabled) = 0; - - /** - * Determines whether or not multithreaded model evaluations are disabled. - * - * @return true if only the current thread is used to evaluate models. - */ - virtual bool isThreadPoolDisabled() const = 0; - - /** - * Provides the maximum number of threads used to determine sparse Jacobians - * and sparse Hessians for the models in this library. - * This value is only used by the models if they were compiled with - * multithreading support. - * - * @return the maximum number of threads - */ - virtual unsigned int getThreadNumber() const = 0; - - /** - * Defines the maximum number of threads used to determine sparse Jacobians - * and sparse Hessians for the models in this library. - * This value is only used by the models if they were compiled with - * multithreading support. - * It should be defined before using the models. - * - * @param n the maximum number of threads - */ - virtual void setThreadNumber(unsigned int n) = 0; - - /** - * Provides the thread scheduling strategy used to determine sparse Jacobians - * and sparse Hessians for the models in this library. - * This value is only used by the models if they were compiled with - * multithreading support. - * - * @return the thread scheduling strategy - */ - virtual ThreadPoolScheduleStrategy getThreadPoolSchedulerStrategy() const = 0; - - /** - * Defines the thread scheduling strategy used to determine sparse Jacobians - * and sparse Hessians for the models in this library. - * This value is only used by the models if they were compiled with - * multithreading support. - * It should be defined before using the models. - * - * @param s the thread scheduling strategy - */ - virtual void setThreadPoolSchedulerStrategy(ThreadPoolScheduleStrategy s) = 0; - - virtual void setThreadPoolVerbose(bool v) = 0; - - virtual bool isThreadPoolVerbose() const = 0; - - virtual void setThreadPoolGuidedMaxWork(float v) = 0; - - virtual float getThreadPoolGuidedMaxWork() const = 0; - - /** - * Defines the number of time measurements taken by each computational - * task during multithreaded model evaluations. This is used to schedule - * work accross threads. The higher the value the more accurate the - * time estimations are but it requires additional calls to retrieve times. - * This value is only used by the models if they were compiled with - * multithreading support. - * - * @param n the number of time measurements to take per task. - */ - virtual void setThreadPoolNumberOfTimeMeas(unsigned int n) = 0; - - - /** - * Provides the number of time measurements taken by each computational - * task during multithreaded model evaluations. This is used to schedule - * work accross threads. The higher the value the more accurate the - * time estimations are but it requires additional calls to retrieve times. - * This value is only used by the models if they were compiled with - * multithreading support. - * - * @return the number of time measurements to take per task. - */ - virtual unsigned int getThreadPoolNumberOfTimeMeas() const = 0; - - inline virtual ~ModelLibrary() { - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/model_library_c_source_gen.hpp b/ct_core/include/ct/external/cppad/cg/model/model_library_c_source_gen.hpp deleted file mode 100644 index d187f9eb6..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/model_library_c_source_gen.hpp +++ /dev/null @@ -1,198 +0,0 @@ -#ifndef CPPAD_CG_MODEL_LIBRARY_C_SOURCE_GEN_INCLUDED -#define CPPAD_CG_MODEL_LIBRARY_C_SOURCE_GEN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Generates C source code for a bundle of models. - * - * @author Joao Leal - */ -template -class ModelLibraryCSourceGen : public JobTimer { -public: - static const std::string FUNCTION_VERSION; - static const std::string FUNCTION_MODELS; - static const std::string FUNCTION_ONCLOSE; - static const std::string FUNCTION_SETTHREADPOOLDISABLED; - static const std::string FUNCTION_ISTHREADPOOLDISABLED; - static const std::string FUNCTION_SETTHREADS; - static const std::string FUNCTION_GETTHREADS; - static const std::string FUNCTION_SETTHREADSCHEDULERSTRAT; - static const std::string FUNCTION_GETTHREADSCHEDULERSTRAT; - static const std::string FUNCTION_SETTHREADPOOLVERBOSE; - static const std::string FUNCTION_ISTHREADPOOLVERBOSE; - static const std::string FUNCTION_SETTHREADPOOLGUIDEDMAXGROUPWORK; - static const std::string FUNCTION_GETTHREADPOOLGUIDEDMAXGROUPWORK; - static const std::string FUNCTION_SETTHREADPOOLNUMBEROFTIMEMEAS; - static const std::string FUNCTION_GETTHREADPOOLNUMBEROFTIMEMEAS; - static const unsigned long API_VERSION; -protected: - static const std::string CONST; -protected: - /** - * Models to be contained whithin the library - */ - std::map*> _models; - /** - * custom functions to be compiled in the dynamic library - */ - std::map _customSource; - /** - * Library level generated source files - */ - std::map _libSources; - /** - * Parallelization type for the sparse Jacobian and sparse Hessian - * (experimental). - * Parallelization can be disabled locally for each model. - */ - MultiThreadingType _multiThreading; - /** - * temporary stream to generate source code - */ - std::ostringstream _cache; -public: - - /** - * Creates a new helper class for the generation of dynamic libraries - * using the C language. - * - * @param model A model compilation helper (must only be deleted after - * this object) - */ - inline ModelLibraryCSourceGen(ModelCSourceGen& model): - _multiThreading(MultiThreadingType::NONE) { - CPPADCG_ASSERT_KNOWN(_models.find(model.getName()) == _models.end(), - "Another model with the same name was already registered"); - - _models[model.getName()] = &model; // must not use initializer_list constructor of map! - } - - template - inline ModelLibraryCSourceGen(ModelCSourceGen& headModel, Ms&... rest) : - ModelLibraryCSourceGen(rest...) { - CPPADCG_ASSERT_KNOWN(_models.find(headModel.getName()) == _models.end(), - "Another model with the same name was already registered"); - - _models[headModel.getName()] = &headModel; - } - - ModelLibraryCSourceGen(const ModelLibraryCSourceGen&) = delete; - ModelLibraryCSourceGen& operator=(const ModelLibraryCSourceGen&) = delete; - - virtual ~ModelLibraryCSourceGen() { - } - - /** - * Adds additional models to be compiled into the created library. - * - * @param model a model compilation helper (must only be deleted after - * this object) - */ - inline void addModel(ModelCSourceGen& model) { - CPPADCG_ASSERT_KNOWN(_models.find(model.getName()) == _models.end(), - "Another model with the same name was already registered"); - - _models[model.getName()] = &model; - - _libSources.clear(); // must regenerate library sources again - } - - inline const std::map*>& getModels() const { - return _models; - } - - void addCustomFunctionSource(const std::string& filename, const std::string& source) { - CPPADCG_ASSERT_KNOWN(!filename.empty(), "The filename name cannot be empty"); - - _customSource[filename] = source; - } - - /** - * Provides the user defined custom sources. - * - * @return maps filenames to the file content for the user defined - * sources. - */ - inline const std::map& getCustomSources() const { - return _customSource; - } - - /** - * Defines whether or not to generate multithreading directives to - * parallelize the sparse Jacobian and sparse Hessian evaluation. - * Parallelization can be disabled locally for each model. - * - * @return multithreading support type - */ - inline MultiThreadingType getMultiThreading() const { - return _multiThreading; - } - - /** - * Defines whether or not to generate multithreading directives to - * parallelize the sparse Jacobian and sparse Hessian evaluation. - * Parallelization can be disabled locally for each model. - * Do not forget to add the appropriate compiler and linker flags - * when multithreading is enabled. - * - * @param multiThreading multithreading support type - */ - inline void setMultiThreading(MultiThreadingType multiThreading) { - _multiThreading = multiThreading; - } - - /** - * Saves the generated C source code into several files. - * - * @param sourcesFolder A directory path where the files should be - * created (any existing files with the same names - * will be overridden). - */ - void saveSources(const std::string& sourcesFolder); - - /** - * Provides the sources for the model library level. - * These sources include, for instance, functions to retrieve the list of - * models contained in the library. - * This does not include the sources for the models. - * - * @return model library sources - */ - virtual const std::map& getLibrarySources(); -protected: - - virtual void generateVersionSource(std::map& sources); - - virtual void generateModelsSource(std::map& sources); - - virtual void generateOnCloseSource(std::map& sources); - - virtual void generateThreadPoolSources(std::map& sources); - - static void saveSources(const std::string& sourcesFolder, - const std::map& sources); - - friend class ModelLibraryProcessor; -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/model_library_c_source_gen_impl.hpp b/ct_core/include/ct/external/cppad/cg/model/model_library_c_source_gen_impl.hpp deleted file mode 100644 index a98073942..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/model_library_c_source_gen_impl.hpp +++ /dev/null @@ -1,364 +0,0 @@ -#ifndef CPPAD_CG_MODEL_LIBRARY_C_SOURCE_GEN_IMPL_INCLUDED -#define CPPAD_CG_MODEL_LIBRARY_C_SOURCE_GEN_IMPL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include - -namespace CppAD { -namespace cg { - -template -const unsigned long ModelLibraryCSourceGen::API_VERSION = 6; - -template -const std::string ModelLibraryCSourceGen::FUNCTION_VERSION = "cppad_cg_version"; - -template -const std::string ModelLibraryCSourceGen::FUNCTION_MODELS = "cppad_cg_models"; - -template -const std::string ModelLibraryCSourceGen::FUNCTION_ONCLOSE = "cppad_cg_on_close"; - -template -const std::string ModelLibraryCSourceGen::FUNCTION_SETTHREADPOOLDISABLED = "cppad_cg_set_thread_pool_disabled"; - -template -const std::string ModelLibraryCSourceGen::FUNCTION_ISTHREADPOOLDISABLED = "cppad_cg_is_thread_pool_disabled"; - -template -const std::string ModelLibraryCSourceGen::FUNCTION_SETTHREADS = "cppad_cg_set_thread_number"; - -template -const std::string ModelLibraryCSourceGen::FUNCTION_GETTHREADS = "cppad_cg_get_thread_number"; - -template -const std::string ModelLibraryCSourceGen::FUNCTION_SETTHREADSCHEDULERSTRAT = "cppad_cg_thpool_set_scheduler_strategy"; - -template -const std::string ModelLibraryCSourceGen::FUNCTION_GETTHREADSCHEDULERSTRAT = "cppad_cg_thpool_get_scheduler_strategy"; - -template -const std::string ModelLibraryCSourceGen::FUNCTION_SETTHREADPOOLVERBOSE = "cppad_cg_thpool_set_verbose"; - -template -const std::string ModelLibraryCSourceGen::FUNCTION_ISTHREADPOOLVERBOSE = "cppad_cg_thpool_is_verbose"; - -template -const std::string ModelLibraryCSourceGen::FUNCTION_SETTHREADPOOLGUIDEDMAXGROUPWORK = "cppad_cg_thpool_set_guided_maxgroupwork"; - -template -const std::string ModelLibraryCSourceGen::FUNCTION_GETTHREADPOOLGUIDEDMAXGROUPWORK = "cppad_cg_thpool_get_guided_maxgroupwork"; - -template -const std::string ModelLibraryCSourceGen::FUNCTION_SETTHREADPOOLNUMBEROFTIMEMEAS = "cppad_cg_thpool_set_number_of_time_meas"; - -template -const std::string ModelLibraryCSourceGen::FUNCTION_GETTHREADPOOLNUMBEROFTIMEMEAS = "cppad_cg_thpool_get_number_of_time_meas"; - -template -const std::string ModelLibraryCSourceGen::CONST = "const"; - -template -void ModelLibraryCSourceGen::saveSources(const std::string& sourcesFolder) { - - // create the folder if it does not exist - system::createFolder(sourcesFolder); - - // save/generate model sources - for (const auto& it : _models) { - saveSources(sourcesFolder, it.second->getSources()); - } - - // save/generate library sources - saveSources(sourcesFolder, getLibrarySources()); - - // save custom user sources - saveSources(sourcesFolder, getCustomSources()); -} - -template -void ModelLibraryCSourceGen::saveSources(const std::string& sourcesFolder, - const std::map& sources) { - for (const auto& it : sources) { - // for debugging purposes only - std::ofstream sourceFile; - std::string file = system::createPath(sourcesFolder, it.first); - sourceFile.open(file.c_str()); - sourceFile << it.second; - sourceFile.close(); - } -} - -template -const std::map& ModelLibraryCSourceGen::getLibrarySources() { - if (_libSources.empty()) { - generateVersionSource(_libSources); - generateModelsSource(_libSources); - generateOnCloseSource(_libSources); - generateThreadPoolSources(_libSources); - - if(_multiThreading != MultiThreadingType::NONE) { - bool usingMultiThreading = false; - for (const auto& it : _models) { - if (it.second->isJacobianMultiThreadingEnabled() || it.second->isHessianMultiThreadingEnabled()) { - usingMultiThreading = true; - break; - } - } - - if (usingMultiThreading) { - if (_multiThreading == MultiThreadingType::PTHREADS) { - _libSources["thread_pool.c"] = CPPADCG_PTHREAD_POOL_C_FILE; - - } else if (_multiThreading == MultiThreadingType::OPENMP) { - _libSources["thread_pool.c"] = CPPADCG_OPENMP_C_FILE; - } - } - } - } - - return _libSources; -} - -template -void ModelLibraryCSourceGen::generateVersionSource(std::map& sources) { - _cache.str(""); - _cache << "unsigned long " << FUNCTION_VERSION << "() {\n" - << " return " << API_VERSION << "u;\n" - << "}\n\n"; - - sources[FUNCTION_VERSION + ".c"] = _cache.str(); -} - -template -void ModelLibraryCSourceGen::generateModelsSource(std::map& sources) { - _cache.str(""); - _cache << "void " << FUNCTION_MODELS << "(char const *const** names, int* count) {\n" - " static const char* const models[] = {\n"; - - for (auto it = _models.begin(); it != _models.end(); ++it) { - if (it != _models.begin()) { - _cache << ",\n"; - } - _cache << " \"" << it->first << "\""; - } - _cache << "};\n" - " *names = models;\n" - " *count = " << _models.size() << ";\n" - "}\n\n"; - - sources[FUNCTION_MODELS + ".c"] = _cache.str(); -} - -template -void ModelLibraryCSourceGen::generateOnCloseSource(std::map& sources) { - bool pthreads = false; - if(_multiThreading == MultiThreadingType::PTHREADS) { - for (const auto& it : _models) { - if (it.second->isJacobianMultiThreadingEnabled() || it.second->isHessianMultiThreadingEnabled()) { - pthreads = true; - break; - } - } - } - - _cache.str(""); - if (pthreads) { - _cache << CPPADCG_PTHREAD_POOL_H_FILE << "\n\n"; - } - _cache << "void " << FUNCTION_ONCLOSE << "() {\n"; - if (pthreads) { - _cache << "cppadcg_thpool_shutdown();\n"; - } - _cache << "}\n\n"; - - sources[FUNCTION_ONCLOSE + ".c"] = _cache.str(); -} - -template -void ModelLibraryCSourceGen::generateThreadPoolSources(std::map& sources) { - - bool usingMultiThreading = false; - if(_multiThreading != MultiThreadingType::NONE) { - for (const auto& it : _models) { - if (it.second->isJacobianMultiThreadingEnabled() || it.second->isHessianMultiThreadingEnabled()) { - usingMultiThreading = true; - break; - } - } - } - - if (usingMultiThreading && _multiThreading == MultiThreadingType::PTHREADS) { - _cache.str(""); - _cache << CPPADCG_PTHREAD_POOL_H_FILE << "\n\n"; - - _cache << "void " << FUNCTION_SETTHREADPOOLDISABLED << "(int disabled) {\n"; - _cache << " cppadcg_thpool_set_disabled(disabled);\n"; - _cache << "}\n\n"; - - _cache << "int " << FUNCTION_ISTHREADPOOLDISABLED << "() {\n"; - _cache << " return cppadcg_thpool_is_disabled();\n"; - _cache << "}\n\n"; - - _cache << "void " << FUNCTION_SETTHREADS << "(unsigned int n) {\n"; - _cache << " cppadcg_thpool_set_threads(n);\n"; - _cache << "}\n\n"; - - _cache << "unsigned int " << FUNCTION_GETTHREADS << "() {\n"; - _cache << " return cppadcg_thpool_get_threads();\n"; - _cache << "}\n\n"; - - _cache << "void " << FUNCTION_SETTHREADSCHEDULERSTRAT << "(enum ScheduleStrategy s) {\n"; - _cache << " cppadcg_thpool_set_scheduler_strategy(s);\n"; - _cache << "}\n\n"; - - _cache << "enum ScheduleStrategy " << FUNCTION_GETTHREADSCHEDULERSTRAT << "() {\n"; - _cache << " return cppadcg_thpool_get_scheduler_strategy();\n"; - _cache << "}\n\n"; - - _cache << "void " << FUNCTION_SETTHREADPOOLVERBOSE << "(int v) {\n"; - _cache << " cppadcg_thpool_set_verbose(v);\n"; - _cache << "}\n\n"; - - _cache << "int " << FUNCTION_ISTHREADPOOLVERBOSE << "() {\n"; - _cache << " return cppadcg_thpool_is_verbose();\n"; - _cache << "}\n\n"; - - _cache << "void " << FUNCTION_SETTHREADPOOLGUIDEDMAXGROUPWORK << "(float v) {\n"; - _cache << " cppadcg_thpool_set_guided_maxgroupwork(v);\n"; - _cache << "}\n\n"; - - _cache << "float " << FUNCTION_GETTHREADPOOLGUIDEDMAXGROUPWORK << "() {\n"; - _cache << " return cppadcg_thpool_get_guided_maxgroupwork();\n"; - _cache << "}\n\n"; - - _cache << "void " << FUNCTION_SETTHREADPOOLNUMBEROFTIMEMEAS << "(unsigned int n) {\n"; - _cache << " cppadcg_thpool_set_n_time_meas(n);\n"; - _cache << "}\n\n"; - - _cache << "unsigned int " << FUNCTION_GETTHREADPOOLNUMBEROFTIMEMEAS << "() {\n"; - _cache << " return cppadcg_thpool_get_n_time_meas();\n"; - _cache << "}\n\n"; - - sources["thread_pool_access.c"] = _cache.str(); - - } else if(usingMultiThreading && _multiThreading == MultiThreadingType::OPENMP) { - _cache.str(""); - _cache << "#include \n"; - _cache << CPPADCG_OPENMP_H_FILE << "\n\n"; - - _cache << "void " << FUNCTION_SETTHREADPOOLDISABLED << "(int disabled) {\n"; - _cache << " cppadcg_openmp_set_disabled(disabled);\n"; - _cache << "}\n\n"; - - _cache << "int " << FUNCTION_ISTHREADPOOLDISABLED << "() {\n"; - _cache << " return cppadcg_openmp_is_disabled();\n"; - _cache << "}\n\n"; - - _cache << "void " << FUNCTION_SETTHREADS << "(unsigned int n) {\n"; - _cache << " cppadcg_openmp_set_threads(n);\n"; - _cache << "}\n\n"; - - _cache << "unsigned int " << FUNCTION_GETTHREADS << "() {\n"; - _cache << " return cppadcg_openmp_get_threads();\n"; - _cache << "}\n\n"; - - _cache << "void " << FUNCTION_SETTHREADSCHEDULERSTRAT << "(enum ScheduleStrategy s) {\n"; - _cache << " cppadcg_openmp_set_scheduler_strategy(s);\n"; - _cache << "}\n\n"; - - _cache << "enum ScheduleStrategy " << FUNCTION_GETTHREADSCHEDULERSTRAT << "() {\n"; - _cache << " return cppadcg_openmp_get_scheduler_strategy();\n"; - _cache << "}\n\n"; - - _cache << "void " << FUNCTION_SETTHREADPOOLVERBOSE << "(int v) {\n"; - _cache << " cppadcg_openmp_set_verbose(v);\n"; - _cache << "}\n\n"; - - _cache << "int " << FUNCTION_ISTHREADPOOLVERBOSE << "() {\n"; - _cache << " return cppadcg_openmp_is_verbose();\n"; - _cache << "}\n\n"; - - _cache << "void " << FUNCTION_SETTHREADPOOLGUIDEDMAXGROUPWORK << "(float v) {\n"; - _cache << "}\n\n"; - - _cache << "float " << FUNCTION_GETTHREADPOOLGUIDEDMAXGROUPWORK << "() {\n"; - _cache << " return 1.0;\n"; - _cache << "}\n\n"; - - _cache << "void " << FUNCTION_SETTHREADPOOLNUMBEROFTIMEMEAS << "(unsigned int n) {\n"; - _cache << "}\n\n"; - - _cache << "unsigned int " << FUNCTION_GETTHREADPOOLNUMBEROFTIMEMEAS << "() {\n"; - _cache << " return 0;\n"; - _cache << "}\n\n"; - - sources["thread_pool_access.c"] = _cache.str(); - - } else { - _cache.str(""); - _cache << "enum ScheduleStrategy {SCHED_STATIC = 1, SCHED_DYNAMIC = 2, SCHED_GUIDED = 3};\n" - "\n"; - _cache << "void " << FUNCTION_SETTHREADPOOLDISABLED << "(int disabled) {\n"; - _cache << "}\n\n"; - - _cache << "int " << FUNCTION_ISTHREADPOOLDISABLED << "() {\n"; - _cache << " return 1;\n"; - _cache << "}\n\n"; - - _cache << "void " << FUNCTION_SETTHREADS << "(unsigned int n) {\n"; - _cache << "}\n\n"; - - _cache << "unsigned int " << FUNCTION_GETTHREADS << "() {\n"; - _cache << " return 1;\n"; - _cache << "}\n\n"; - - _cache << "void " << FUNCTION_SETTHREADSCHEDULERSTRAT << "(enum ScheduleStrategy s) {\n"; - _cache << "}\n\n"; - - _cache << "enum ScheduleStrategy " << FUNCTION_GETTHREADSCHEDULERSTRAT << "() {\n"; - _cache << " return SCHED_STATIC;\n"; - _cache << "}\n\n"; - - _cache << "void " << FUNCTION_SETTHREADPOOLVERBOSE << "(int v) {\n"; - _cache << "}\n\n"; - - _cache << "int " << FUNCTION_ISTHREADPOOLVERBOSE << "() {\n"; - _cache << " return 0;\n"; - _cache << "}\n\n"; - - _cache << "void " << FUNCTION_SETTHREADPOOLGUIDEDMAXGROUPWORK << "(float v) {\n"; - _cache << "}\n\n"; - - _cache << "float " << FUNCTION_GETTHREADPOOLGUIDEDMAXGROUPWORK << "() {\n"; - _cache << " return 1.0;\n"; - _cache << "}\n\n"; - - _cache << "void " << FUNCTION_SETTHREADPOOLNUMBEROFTIMEMEAS << "(unsigned int n) {\n"; - _cache << "}\n\n"; - - _cache << "unsigned int " << FUNCTION_GETTHREADPOOLNUMBEROFTIMEMEAS << "() {\n"; - _cache << " return 0;\n"; - _cache << "}\n\n"; - - sources["thread_pool_access.c"] = _cache.str(); - } -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/model_library_processor.hpp b/ct_core/include/ct/external/cppad/cg/model/model_library_processor.hpp deleted file mode 100644 index 62f6d6c37..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/model_library_processor.hpp +++ /dev/null @@ -1,54 +0,0 @@ -#ifndef CPPAD_CG_MODEL_LIBRARY_PROCESSOR_INCLUDED -#define CPPAD_CG_MODEL_LIBRARY_PROCESSOR_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Uses source code generated by a model library source-code generator. - * - * @author Joao Leal - */ -template -class ModelLibraryProcessor { -protected: - ModelLibraryCSourceGen* modelLibraryHelper_; -public: - - inline ModelLibraryProcessor(ModelLibraryCSourceGen& modelLibraryHelper) : - modelLibraryHelper_(&modelLibraryHelper) { - } - - inline virtual ~ModelLibraryProcessor() { - } - -protected: - - inline const std::map& getLibrarySources() { - return modelLibraryHelper_->getLibrarySources(); - } - - inline const std::map& getSources(ModelCSourceGen& model) { - return model.getSources(modelLibraryHelper_->getMultiThreading(), modelLibraryHelper_); - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/patterns/hessian_with_loops_info.hpp b/ct_core/include/ct/external/cppad/cg/model/patterns/hessian_with_loops_info.hpp deleted file mode 100644 index 8231805d7..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/patterns/hessian_with_loops_info.hpp +++ /dev/null @@ -1,163 +0,0 @@ -#ifndef CPPAD_CG_HESSIAN_WITH_LOOPS_INFO_INCLUDED -#define CPPAD_CG_HESSIAN_WITH_LOOPS_INFO_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -namespace loops { - -template -class HessianWithLoopsEquationGroupInfo { -public: - std::vector > evalHessSparsity; - // (tapeJ1, tapeJ2) -> [positions] - std::map > indexedIndexedPositions; - // (tapeJ1, tapeJ2(j2)) -> [positions] - std::map > indexedNonIndexedPositions; - // (tapeJ1, j2) -> [positions] - std::map > indexedTempPositions; - // (tapeJ1(j1), tapeJ2) -> [positions] - std::map > nonIndexedIndexedPositions; - // (j1, tapeJ2) -> [positions] - std::map > tempIndexedPositions; - // (tapeJ1, j2) -> [k] - std::map > indexedTempEvals; - // [(j1, j2)] - std::set nonIndexedNonIndexedEvals; - // (j2, j1) -> [k] - std::map > nonIndexedTempEvals; - // (j1, j2) -> [k1] - std::map > tempNonIndexedEvals; - // (j1, j2) -> k1 -> [k2] - std::map > > tempTempEvals; - /** - * Hessian - */ - std::map > > hess; - - inline HessianWithLoopsEquationGroupInfo() { - } - - inline HessianWithLoopsEquationGroupInfo(const LoopModel& loop) : - evalHessSparsity(loop.getTapeIndependentCount()) { - - } -}; - -template -class HessianWithLoopsInfo { -public: - LoopModel* model; - // - std::vector > evalJacSparsity; - // - std::vector > equationGroups; - //(j1, j2) -> position - std::map nonIndexedNonIndexedPosition; - // (j1 ,j2) -> [k1] - std::map > nonLoopNonIndexedNonIndexed; - - LoopStartOperationNode* loopStart; - LoopEndOperationNode* loopEnd; - IndexOperationNode* iterationIndexOp; - std::vector > x; // loop independent variables - std::vector > w; - /** - * Jacobian - */ - std::vector > > dyiDzk; - std::vector > noLoopEvalHessTempsSparsity; - std::map > > dzDxx; - - // if-else branches - std::vector > ifElses; - - inline HessianWithLoopsInfo() : - model(nullptr), - loopStart(nullptr), - loopEnd(nullptr), - iterationIndexOp(nullptr) { - - } - - inline HessianWithLoopsInfo(LoopModel& loop) : - model(&loop), - evalJacSparsity(loop.getTapeDependentCount()), - equationGroups(loop.getEquationsGroups().size(), HessianWithLoopsEquationGroupInfo(loop)), - loopStart(nullptr), - loopEnd(nullptr), - iterationIndexOp(nullptr) { - - } - - /** - * Evaluates the Jacobian and the Hessian of the loop model - * - * @param individualColoring whether or not there are atomic - * functions in the model - */ - inline void evalLoopModelJacobianHessian(bool individualColoring) { - using std::vector; - - ADFun >& fun = model->getTape(); - const std::vector >& eqGroups = model->getEquationsGroups(); - - vector > > vw(1); - vw[0].resize(w.size()); - - vector > y; - - size_t nEqGroups = equationGroups.size(); - - vector > empty; - vector > > emptyJac; - - for (size_t g = 0; g < nEqGroups; g++) { - const IterEquationGroup& group = eqGroups[g]; - - vector > > > vhess; - - for (size_t i = 0; i < w.size(); i++) { - vw[0][i] = Base(0); - } - - for (size_t itI : group.tapeI) { - vw[0][itI] = w[itI]; - } - - generateLoopForJacHes(fun, x, vw, y, - model->getJacobianSparsity(), - g == 0 ? evalJacSparsity : empty, - g == 0 ? dyiDzk : emptyJac, - model->getHessianSparsity(), - equationGroups[g].evalHessSparsity, - vhess, - individualColoring); - - //Hessian - equationGroups[g].hess = vhess[0]; - } - } - -}; - -} // END loops namespace - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops.hpp b/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops.hpp deleted file mode 100644 index 00bf0336e..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops.hpp +++ /dev/null @@ -1,1280 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -namespace loops { - -/*********************************************************************** - * Utility classes - **********************************************************************/ -template -class IfBranchData { -public: - CG value; - std::map locations; -public: - - inline IfBranchData() { - } - - inline IfBranchData(const CG& v, - const std::map& loc) : - value(v), - locations(loc) { - } -}; - -template -class IfBranchInfo { -public: - std::set iterations; - OperationNode* node; -}; - -template -class IfElseInfo { -public: - std::map > firstIt2Branch; - OperationNode* endIf; - - inline IfElseInfo() : - endIf(nullptr) { - } -}; - -class JacobianWithLoopsRowInfo { -public: - // tape J index -> {locationIt0, locationIt1, ...} - std::map > indexedPositions; - - // original J index -> {locationIt0, locationIt1, ...} - std::map > nonIndexedPositions; - - // original J index - std::set nonIndexedEvals; - - // original J index -> k index - std::map > tmpEvals; -}; - -template -class IndexedDependentLoopInfo { -public: - std::vector indexes; - std::vector > origVals; - IndexPattern* pattern; - - inline IndexedDependentLoopInfo() : - pattern(nullptr) { - } -}; - -template -inline std::vector > createIndexedIndependents(CodeHandler& handler, - LoopModel& loop, - IndexOperationNode& iterationIndexOp) { - - const std::vector >& indexedIndepIndexes = loop.getIndexedIndepIndexes(); - size_t nIndexed = indexedIndepIndexes.size(); - - std::vector > x(nIndexed); // zero order - - std::vector > xIndexedArgs{iterationIndexOp}; - std::vector info(2); - info[0] = 0; // tx - - for (size_t j = 0; j < nIndexed; j++) { - info[1] = handler.addLoopIndependentIndexPattern(*loop.getIndependentIndexPatterns()[j], j); - x[j] = CG(*handler.makeNode(CGOpCode::LoopIndexedIndep, info, xIndexedArgs)); - } - - return x; -} - -template -inline std::vector > createLoopIndependentVector(CodeHandler& handler, - LoopModel& loop, - const std::vector >& indexedIndeps, - const std::vector >& nonIndexed, - const std::vector >& nonIndexedTmps) { - - const std::vector >& indexedIndepIndexes = loop.getIndexedIndepIndexes(); - const std::vector& nonIndexedIndepIndexes = loop.getNonIndexedIndepIndexes(); - const std::vector& temporaryIndependents = loop.getTemporaryIndependents(); - - size_t nIndexed = indexedIndepIndexes.size(); - size_t nNonIndexed = nonIndexedIndepIndexes.size(); - size_t nTape = nIndexed + nNonIndexed + temporaryIndependents.size(); - - // indexed independents - std::vector > x(nTape); - for (size_t j = 0; j < nIndexed; j++) { - x[j] = indexedIndeps[j]; - } - - // non indexed - for (size_t j = 0; j < nNonIndexed; j++) { - x[nIndexed + j] = nonIndexed[nonIndexedIndepIndexes[j].original]; - } - - // temporaries - for (size_t j = 0; j < temporaryIndependents.size(); j++) { - x[nIndexed + nNonIndexed + j] = nonIndexedTmps[temporaryIndependents[j].original]; - } - - return x; -} - -template -inline std::vector > createLoopDependentVector(CodeHandler& handler, - LoopModel& loop, - IndexOperationNode& iterationIndexOp) { - - const std::vector& depIndexes = loop.getDependentIndexPatterns(); - std::vector > deps(depIndexes.size()); - - size_t dep_size = depIndexes.size(); - size_t x_size = loop.getTapeIndependentCount(); - - std::vector > xIndexedArgs{iterationIndexOp}; - std::vector info(2); - info[0] = 2; // py2 - - for (size_t i = 0; i < dep_size; i++) { - IndexPattern* ip = depIndexes[i]; - info[1] = handler.addLoopIndependentIndexPattern(*ip, x_size + i); // dependent index pattern location - deps[i] = CG(*handler.makeNode(CGOpCode::LoopIndexedIndep, info, xIndexedArgs)); - } - - return deps; -} - -template -inline CG createLoopDependentFunctionResult(CodeHandler& handler, - size_t i, const CG& val, IndexPattern* ip, - IndexOperationNode& iterationIndexOp) { - - size_t assignOrAdd = 1; // add - - if (ip != nullptr) { - // {dependent index pattern location, } - std::vector aInfo{handler.addLoopDependentIndexPattern(*ip), assignOrAdd}; - // {indexed expression, index(jrowIndexOp) } - std::vector > indexedArgs{asArgument(val), iterationIndexOp}; - - OperationNode* yIndexed = handler.makeNode(CGOpCode::LoopIndexedDep, aInfo, indexedArgs); - - return handler.createCG(Argument(*yIndexed)); - - } else if (val.getOperationNode() != nullptr && - val.getOperationNode()->getOperationType() == CGOpCode::EndIf) { - - // {i} : points to itself - return handler.createCG(*handler.makeNode(CGOpCode::DependentRefRhs,{i}, {*val.getOperationNode()})); - - } else { - return val; - } -} - -/*************************************************************************** - * Methods related with loop insertion into the operation graph - **************************************************************************/ - -template -LoopEndOperationNode* createLoopEnd(CodeHandler& handler, - LoopStartOperationNode& loopStart, - const std::vector, IndexPattern*> >& indexedLoopResults, - const std::set*>& indexesOps, - size_t assignOrAdd) { - std::vector > endArgs; - std::vector > indexedArgs(1 + indexesOps.size()); - std::vector info(2); - - size_t dep_size = indexedLoopResults.size(); - endArgs.reserve(dep_size); - - for (size_t i = 0; i < dep_size; i++) { - const std::pair, IndexPattern*>& depInfo = indexedLoopResults[i]; - if (depInfo.second != nullptr) { - indexedArgs.resize(1); - - indexedArgs[0] = asArgument(depInfo.first); // indexed expression - for (IndexOperationNode* itIndexOp : indexesOps) { - indexedArgs.push_back(*itIndexOp); // dependency on the index - } - - info[0] = handler.addLoopDependentIndexPattern(*depInfo.second); // dependent index pattern location - info[1] = assignOrAdd; - - OperationNode* yIndexed = handler.makeNode(CGOpCode::LoopIndexedDep, info, indexedArgs); - endArgs.push_back(*yIndexed); - } else { - OperationNode* n = depInfo.first.getOperationNode(); - CPPADCG_ASSERT_UNKNOWN(n != nullptr); - endArgs.push_back(*n); - } - } - - LoopEndOperationNode* loopEnd = handler.makeLoopEndNode(loopStart, endArgs); - - return loopEnd; -} - -template -inline void moveNonIndexedOutsideLoop(CodeHandler& handler, - LoopStartOperationNode& loopStart, - LoopEndOperationNode& loopEnd) { - //EquationPattern::uncolor(dependents[dep].getOperationNode()); - const OperationNode& loopIndex = loopStart.getIndex(); - std::set*> nonIndexed; - - CodeHandlerVector indexed(handler); // 0 - unknown, 1 - non-indexed, 2 - indexed - indexed.adjustSize(); - indexed.fill(0); - - const std::vector >& endArgs = loopEnd.getArguments(); - for (size_t i = 0; i < endArgs.size(); i++) { - CPPADCG_ASSERT_UNKNOWN(endArgs[i].getOperation() != nullptr); - LoopNonIndexedLocator(handler, indexed, nonIndexed, loopIndex).findNonIndexedNodes(*endArgs[i].getOperation()); - } - - std::vector >& startArgs = loopStart.getArguments(); - - size_t sas = startArgs.size(); - startArgs.resize(sas + nonIndexed.size()); - size_t i = 0; - for (auto it = nonIndexed.begin(); it != nonIndexed.end(); ++it, i++) { - startArgs[sas + i] = **it; - } -} - -template -class LoopNonIndexedLocator { -private: - CodeHandler& handler_; - CodeHandlerVector& indexed_; // 0 - unknown, 1 - non-indexed, 2 - indexed - std::set*>& nonIndexed_; - const OperationNode& loopIndex_; -public: - - inline LoopNonIndexedLocator(CodeHandler& handler, - CodeHandlerVector& indexed, - std::set*>& nonIndexed, - const OperationNode& loopIndex) : - handler_(handler), - indexed_(indexed), - nonIndexed_(nonIndexed), - loopIndex_(loopIndex) { - indexed_.adjustSize(); - } - - inline bool findNonIndexedNodes(OperationNode& node) { - short& idx = indexed_[node]; - if (idx > 0) - return idx == 1; - - if (node.getOperationType() == CGOpCode::IndexDeclaration) { - if (&node == &loopIndex_) { - idx = 2; - return false; // depends on the loop index - } - } - - const std::vector >& args = node.getArguments(); - size_t size = args.size(); - - bool indexedPath = false; // whether or not this node depends on indexed independents - bool nonIndexedArgs = false; // whether or not there are non indexed arguments - for (size_t a = 0; a < size; a++) { - OperationNode* arg = args[a].getOperation(); - if (arg != nullptr) { - bool nonIndexedArg = findNonIndexedNodes(*arg); - nonIndexedArgs |= nonIndexedArg; - indexedPath |= !nonIndexedArg; - } - } - - idx = indexedPath ? 2 : 1; - - if (node.getOperationType() == CGOpCode::ArrayElement || - node.getOperationType() == CGOpCode::AtomicForward || - node.getOperationType() == CGOpCode::AtomicReverse) { - return !indexedPath; // should not move array creation elements outside the loop - } - - if (indexedPath && nonIndexedArgs) { - for (size_t a = 0; a < size; a++) { - OperationNode* arg = args[a].getOperation(); - if (arg != nullptr && indexed_[*arg] == 1) {// must be a non indexed expression - CGOpCode op = arg->getOperationType(); - if (op != CGOpCode::Inv && op != CGOpCode::TmpDcl) {// no point in moving just one variable outside - - if (op == CGOpCode::LoopIndexedTmp) { - // must not place a LoopIndexedTmp operation outside the loop - Argument assignArg = arg->getArguments()[1]; - if (assignArg.getOperation() != nullptr) { // no point in moving a constant value outside - OperationNode* assignNode = handler_.makeNode(CGOpCode::Assign, assignArg); - arg->getArguments()[1] = *assignNode; - nonIndexed_.insert(assignNode); - } - } else { - nonIndexed_.insert(arg); - } - } - } - } - } - - return !indexedPath; - } -}; - -template -inline IfElseInfo* findExistingIfElse(std::vector >& ifElses, - const std::map > >& first2Iterations) { - using namespace std; - - // try to find an existing if-else where these operations can be added - for (size_t f = 0; f < ifElses.size(); f++) { - IfElseInfo& ifElse = ifElses[f]; - - if (first2Iterations.size() != ifElse.firstIt2Branch.size()) - continue; - - bool matches = true; - auto itLoc = first2Iterations.begin(); - auto itBranches = ifElse.firstIt2Branch.begin(); - for (; itLoc != first2Iterations.end(); ++itLoc, ++itBranches) { - if (itLoc->second.second != itBranches->second.iterations) { - matches = false; - break; - } - } - - if (matches) { - return &ifElse; - } - } - - return nullptr; -} - -template -OperationNode* createIndexConditionExpressionOp(CodeHandler& handler, - const std::set& iterations, - const std::set& usedIter, - size_t maxIter, - IndexOperationNode& iterationIndexOp) { - std::vector info = createIndexConditionExpression(iterations, usedIter, maxIter); - OperationNode* node = handler.makeNode(CGOpCode::IndexCondExpr, info,{iterationIndexOp}); - return node; -} - -std::vector createIndexConditionExpression(const std::set& iterations, - const std::set& usedIter, - size_t maxIter) { - CPPADCG_ASSERT_UNKNOWN(!iterations.empty()); - - std::map allIters; - for (size_t it : usedIter) { - allIters[it] = false; - } - for (size_t it : iterations) { - allIters[it] = true; - } - - std::vector info; - info.reserve(iterations.size() / 2 + 2); - - auto it = allIters.begin(); - while (it != allIters.end()) { - auto min = it; - auto max = it; - auto minNew = allIters.end(); - auto maxNew = allIters.end(); - if (it->second) { - minNew = it; - maxNew = it; - } - - for (++it; it != allIters.end(); ++it) { - if (it->first != max->first + 1) { - break; - } - - max = it; - if (it->second) { - if (minNew == allIters.end()) - minNew = it; - maxNew = it; - } - } - - if (minNew != allIters.end()) { - // contains elements from the current iteration set - if (maxNew->first == minNew->first) { - // only one element - info.push_back(minNew->first); - info.push_back(maxNew->first); - } else { - //several elements - if (min->first == 0) - info.push_back(min->first); - else - info.push_back(minNew->first); - - if (max->first == maxIter) - info.push_back(std::numeric_limits::max()); - else - info.push_back(maxNew->first); - } - } - } - - return info; -} - -template -inline CG createConditionalContribution(CodeHandler& handler, - const std::map >& branches, - size_t maxIter, - size_t nLocalIter, - IndexOperationNode& iterationIndexOp, - std::vector >& ifElses, - bool printResult = false) { - using namespace std; - - map > > firstIt2Count2Iterations; - for (const auto& itb : branches) { - set iterations; - mapKeys(itb.second.locations, iterations); - firstIt2Count2Iterations[SizeN1stIt(iterations.size(), *iterations.begin())] = make_pair(itb.first, iterations); - } - - IfElseInfo* ifElseBranches = findExistingIfElse(ifElses, firstIt2Count2Iterations); - bool reusingIfElse = ifElseBranches != nullptr; - if (!reusingIfElse) { - size_t s = ifElses.size(); - ifElses.resize(s + 1); - ifElseBranches = &ifElses[s]; - } - - /** - * create/change each if/else branch - */ - OperationNode* ifStart = nullptr; - OperationNode* ifBranch = nullptr; - Argument nextBranchArg; - set usedIter; - - for (const auto& it1st2Count2Iters : firstIt2Count2Iterations) { - size_t firstIt = it1st2Count2Iters.first.second; - size_t count = it1st2Count2Iters.second.first; - const set& iterations = it1st2Count2Iters.second.second; - const IfBranchData& branchData = branches.at(count); - - size_t iterCount = iterations.size(); - - SizeN1stIt pos(iterCount, firstIt); - - if (reusingIfElse) { - //reuse existing node - ifBranch = ifElseBranches->firstIt2Branch.at(pos).node; - if (nextBranchArg.getOperation() != nullptr) - ifBranch->getArguments().push_back(nextBranchArg); - - } else if (usedIter.size() + iterCount == nLocalIter) { - // all other iterations: ELSE - ifBranch = handler.makeNode(CGOpCode::Else,{Argument(*ifBranch), nextBranchArg}); - } else { - // depends on the iteration index - OperationNode* cond = createIndexConditionExpressionOp(handler, iterations, usedIter, maxIter, iterationIndexOp); - - if (ifStart == nullptr) { - // IF - ifStart = handler.makeNode(CGOpCode::StartIf, *cond); - ifBranch = ifStart; - } else { - // ELSE IF - ifBranch = handler.makeNode(CGOpCode::ElseIf,{*ifBranch, *cond, nextBranchArg}); - } - - usedIter.insert(iterations.begin(), iterations.end()); - } - - IndexPattern* pattern = IndexPattern::detect(branchData.locations); - handler.manageLoopDependentIndexPattern(pattern); - - Argument value; - if (printResult) { - PrintOperationNode* printNode = handler.makePrintNode("__________", asArgument(branchData.value), "\n"); - value = *printNode; - } else { - value = asArgument(branchData.value); - } - - // {dependent index pattern location, assignOrAdd} - std::vector ainfo{handler.addLoopDependentIndexPattern(*pattern), 1}; - // {indexed expression, dependency on the index} - std::vector > indexedArgs{value, iterationIndexOp}; - OperationNode* yIndexed = handler.makeNode(CGOpCode::LoopIndexedDep, ainfo, indexedArgs); - - OperationNode* ifAssign = handler.makeNode(CGOpCode::CondResult,{Argument(*ifBranch), Argument(*yIndexed)}); - nextBranchArg = Argument(*ifAssign); - - if (!reusingIfElse) { - IfBranchInfo& branch = ifElseBranches->firstIt2Branch[pos]; // creates a new if branch - branch.iterations = iterations; - branch.node = ifBranch; - } - } - - /** - * end if - */ - if (reusingIfElse) { - ifElseBranches->endIf->getArguments().push_back(nextBranchArg); - } else { - ifElseBranches->endIf = handler.makeNode(CGOpCode::EndIf,{*ifBranch, nextBranchArg}); - } - - return handler.createCG(Argument(*ifElseBranches->endIf)); -} - -/** - * Contribution to a constant location - */ -template -CG createConditionalContribution(CodeHandler& handler, - LinearIndexPattern& pattern, - const std::set& iterations, - size_t maxIter, - const CG& ddfdxdx, - IndexOperationNode& iterationIndexOp, - std::vector >& ifElses) { - using namespace std; - - CPPADCG_ASSERT_UNKNOWN(pattern.getLinearSlopeDy() == 0); // must be a constant index - - // try to find an existing if-else where these operations can be added - map > > firstIt2Count2Iterations; - SizeN1stIt pos(iterations.size(), *iterations.begin()); - firstIt2Count2Iterations[pos] = make_pair(1, iterations); - - IfElseInfo* ifElseBranches = findExistingIfElse(ifElses, firstIt2Count2Iterations); - bool reusingIfElse = ifElseBranches != nullptr; - if (!reusingIfElse) { - size_t s = ifElses.size(); - ifElses.resize(s + 1); - ifElseBranches = &ifElses[s]; - } - - /** - * create/change each if/else branch - */ - OperationNode* ifBranch = nullptr; - - if (reusingIfElse) { - //reuse existing node - ifBranch = ifElseBranches->firstIt2Branch.at(pos).node; - - } else { - // depends on the iterations indexes - const set usedIter; - OperationNode* cond = createIndexConditionExpressionOp(handler, iterations, usedIter, maxIter, iterationIndexOp); - - ifBranch = handler.makeNode(CGOpCode::StartIf, *cond); - } - - // {dependent index pattern location, assignOrAdd} - std::vector ainfo{handler.addLoopDependentIndexPattern(pattern), 1}; - // {indexed expression, dependency on the index} - std::vector > indexedArgs{asArgument(ddfdxdx), iterationIndexOp}; - - OperationNode* yIndexed = handler.makeNode(CGOpCode::LoopIndexedDep, ainfo, indexedArgs); - - OperationNode* ifAssign = handler.makeNode(CGOpCode::CondResult,{*ifBranch, *yIndexed}); - Argument nextBranchArg = *ifAssign; - - if (!reusingIfElse) { - IfBranchInfo& branch = ifElseBranches->firstIt2Branch[pos]; // creates a new if branch - branch.iterations = iterations; - branch.node = ifBranch; - } - - /** - * end if - */ - if (reusingIfElse) { - ifElseBranches->endIf->getArguments().push_back(nextBranchArg); - } else { - ifElseBranches->endIf = handler.makeNode(CGOpCode::EndIf,{*ifBranch, nextBranchArg}); - } - - return handler.createCG(Argument(*ifElseBranches->endIf)); -} - -/** - * - * @param handler source code handler - * @param locationsIter2Pos maps each iteration to the location of the result - * @param iterCount the number of iteration of the loop - * @param value the value determined inside the loop - * @param pattern the pattern used to save the value - * @param assignOrAdd whether the value is assigned or added to the - * dependent array - * @param iterationIndexOp the iteration index operation for this loop - * @param ifElses conditions used inside the loop - * @return - */ -template -std::pair, IndexPattern*> createLoopResult(CodeHandler& handler, - const std::map& locationsIter2Pos, - size_t iterCount, - const CG& value, - IndexPattern* pattern, - size_t assignOrAdd, - IndexOperationNode& iterationIndexOp, - std::vector >& ifElses) { - using namespace std; - - if (locationsIter2Pos.size() == iterCount) { - // present in all iterations - - return make_pair(value, pattern); - - } else { - /** - * must create a conditional element so that this - * contribution is only evaluated at the relevant iterations - */ - - // try to find an existing if-else where these operations can be added - map > > firstIt2Count2Iterations; - - set iterations; - mapKeys(locationsIter2Pos, iterations); - SizeN1stIt pos(iterations.size(), *iterations.begin()); - firstIt2Count2Iterations[pos] = make_pair(*iterations.begin(), iterations); - - IfElseInfo* ifElseBranches = findExistingIfElse(ifElses, firstIt2Count2Iterations); - bool reusingIfElse = ifElseBranches != nullptr; - if (!reusingIfElse) { - size_t s = ifElses.size(); - ifElses.resize(s + 1); - ifElseBranches = &ifElses[s]; - } - - OperationNode* ifStart; - - if (reusingIfElse) { - //reuse existing node - ifStart = ifElseBranches->firstIt2Branch.at(pos).node; - } else { - // depends on the iterations indexes - set usedIter; - OperationNode* cond = createIndexConditionExpressionOp(handler, iterations, usedIter, iterCount - 1, iterationIndexOp); - - ifStart = handler.makeNode(CGOpCode::StartIf, *cond); - } - - // {dependent index pattern location, } - std::vector ainfo{handler.addLoopDependentIndexPattern(*pattern), assignOrAdd}; - // {indexed expression, dependency on the index} - std::vector > indexedArgs{asArgument(value), iterationIndexOp}; - - OperationNode* yIndexed = handler.makeNode(CGOpCode::LoopIndexedDep, ainfo, indexedArgs); - - OperationNode* ifAssign = handler.makeNode(CGOpCode::CondResult,{*ifStart, *yIndexed}); - - if (!reusingIfElse) { - // existing 'if' with the same iterations - IfBranchInfo& branch = ifElseBranches->firstIt2Branch[pos]; // creates a new if branch - branch.iterations = iterations; - branch.node = ifStart; - } - - if (reusingIfElse) { - ifElseBranches->endIf->getArguments().push_back(*ifAssign); - } else { - ifElseBranches->endIf = handler.makeNode(CGOpCode::EndIf,{*ifStart, *ifAssign}); - } - - IndexPattern* p = nullptr; - return make_pair(handler.createCG(Argument(*ifElseBranches->endIf)), p); - } - -} - -class ArrayElementCopyPattern { -public: - IndexPattern* resultPattern; - IndexPattern* compressedPattern; -public: - - inline ArrayElementCopyPattern() : - resultPattern(nullptr), - compressedPattern(nullptr) { - } - - inline ArrayElementCopyPattern(IndexPattern* resultPat, - IndexPattern* compressedPat) : - resultPattern(resultPat), - compressedPattern(compressedPat) { - } - - inline ~ArrayElementCopyPattern() { - delete resultPattern; - delete compressedPattern; - } - -}; - -class ArrayElementGroup { -public: - std::set keys; - std::vector elements; - - ArrayElementGroup(const std::set& k, size_t size) : - keys(k), - elements(size) { - } -}; - -class ArrayGroup { -public: - std::unique_ptr pattern; - std::unique_ptr startLocPattern; - SmartMapValuePointer elCount2elements; -}; - -/** - * - * @param loopGroups Used elements from the arrays provided by the group - * function calls (loop->group->{array->{compressed position} }) - * @param matrixInfo maps each element to its position - * (array -> [compressed elements { original index }] ) - * @param loopCalls - * @param garbage holds created ArrayGroups - */ -template -inline void determineForRevUsagePatterns(const std::map*, std::map > > >& loopGroups, - const std::map& matrixInfo, - std::map*, std::map > >& loopCalls, - SmartVectorPointer& garbage) { - - using namespace std; - - std::vector arrayStart; - /** - * Determine jcol index patterns and - * array start patterns - */ - std::vector localit2jcols; - for (const auto& itlge : loopGroups) { - LoopModel* loop = itlge.first; - - garbage.reserve(garbage.size() + itlge.second.size()); - - for (const auto& itg : itlge.second) { - size_t group = itg.first; - const map >& jcols2e = itg.second; - - // group by number of iterations - std::unique_ptr data(new ArrayGroup()); - - /** - * jcol pattern - */ - mapKeys(jcols2e, localit2jcols); - data->pattern.reset(IndexPattern::detect(localit2jcols)); - - /** - * array start pattern - */ - bool ordered = true; - for (size_t l = 0; l < localit2jcols.size(); l++) { - if (!matrixInfo.at(localit2jcols[l]).ordered) { - ordered = false; - break; - } - } - - if (ordered) { - arrayStart.resize(localit2jcols.size()); - - for (size_t l = 0; l < localit2jcols.size(); l++) { - const std::vector >& location = matrixInfo.at(localit2jcols[l]).locations; - arrayStart[l] = *location[0].begin(); - } - - data->startLocPattern.reset(IndexPattern::detect(arrayStart)); - } else { - /** - * combine calls to this group function which provide - * the same number of elements - */ - map > elCount2localIt2jcols; - - size_t localIt = 0; - for (auto itJcols2e = jcols2e.begin(); itJcols2e != jcols2e.end(); ++itJcols2e, localIt++) { - size_t elCount = itJcols2e->second.size(); - elCount2localIt2jcols[elCount][localIt] = itJcols2e->first; - } - - for (const auto& elC2jcolIt : elCount2localIt2jcols) { - size_t commonElSize = elC2jcolIt.first; - const map& localIt2keys = elC2jcolIt.second; - - // the same number of elements is always provided in each call - std::vector > compressPos(commonElSize); - std::vector > resultPos(commonElSize); - - set keys; - - for (const auto& lIt2jcolIt : localIt2keys) { - size_t localIt = lIt2jcolIt.first; - size_t key = lIt2jcolIt.second; - - keys.insert(key); - - const std::vector >& origPos = matrixInfo.at(key).locations; - const std::set& compressed = jcols2e.at(key); - - size_t e = 0; - for (auto itE = compressed.begin(); itE != compressed.end(); ++itE, e++) { - CPPADCG_ASSERT_UNKNOWN(origPos[*itE].size() == 1); - resultPos[e][localIt] = *origPos[*itE].begin(); - - compressPos[e][localIt] = *itE; - } - } - - ArrayElementGroup* eg = new ArrayElementGroup(keys, commonElSize); - data->elCount2elements[commonElSize] = eg; - - for (size_t e = 0; e < commonElSize; e++) { - eg->elements[e].resultPattern = IndexPattern::detect(resultPos[e]); - eg->elements[e].compressedPattern = IndexPattern::detect(compressPos[e]); - } - - } - - } - - // group by number of iterations - loopCalls[localit2jcols.size()][loop][group] = data.get(); - garbage.push_back(data.release()); - } - } -} - -/** - * @param loopGroups Used elements from the arrays provided by the group - * function calls (loop->group->{array->{compressed position} }) - * @param nonLoopElements Used elements from non loop function calls - * ([array]{compressed position}) - */ -template -void printForRevUsageFunction(std::ostringstream& out, - const std::string& baseTypeName, - const std::string& modelName, - const std::string& modelFunction, - size_t inLocalSize, - const std::string& localFunction, - const std::string& suffix, - const std::string& keyIndexName, - const std::string& indexIt, - const std::string& resultName, - const std::map*, std::map > > >& loopGroups, - const std::map >& nonLoopElements, - const std::map& matrixInfo, - void (*generateLocalFunctionName)(std::ostringstream& cache, const std::string& modelName, const LoopModel& loop, size_t g), - size_t nnz, - size_t maxCompressedSize) { - using namespace std; - - /** - * determine to which functions we can provide the Hessian row directly - * without needing a temporary array (compressed) - */ - SmartVectorPointer garbage; - map*, map > > loopCalls; - - /** - * Determine jrow index patterns and - * Hessian row start patterns - */ - determineForRevUsagePatterns(loopGroups, matrixInfo, loopCalls, garbage); - - string nlRev2Suffix = "noloop_" + suffix; - - LanguageC langC(baseTypeName); - string loopFArgs = "inLocal, outLocal, " + langC.getArgumentAtomic(); - string argsDcl = langC.generateDefaultFunctionArgumentsDcl(); - - out << "void " << modelFunction << "(" << argsDcl << ") {\n"; - - /** - * Find random index patterns - */ - set indexRandomPatterns; - - for (const auto& itItlg : loopCalls) { - - for (const auto& itlg : itItlg.second) { - - for (const auto& itg : itlg.second) { - ArrayGroup* group = itg.second; - - CodeHandler::findRandomIndexPatterns(group->pattern.get(), indexRandomPatterns); - - if (group->startLocPattern.get() != nullptr) { - CodeHandler::findRandomIndexPatterns(group->startLocPattern.get(), indexRandomPatterns); - - } else { - for (const auto& itc : group->elCount2elements) { - const ArrayElementGroup* eg = itc.second; - - for (const ArrayElementCopyPattern& ePos : eg->elements) { - CodeHandler::findRandomIndexPatterns(ePos.resultPattern, indexRandomPatterns); - CodeHandler::findRandomIndexPatterns(ePos.compressedPattern, indexRandomPatterns); - } - } - } - } - } - } - - /** - * static variables - */ - LanguageC::generateNames4RandomIndexPatterns(indexRandomPatterns); - LanguageC::printRandomIndexPatternDeclaration(out, " ", indexRandomPatterns); - - /** - * local variables - */ - out << " " << baseTypeName << " const * inLocal[" << inLocalSize << "];\n" - " " << baseTypeName << " inLocal1 = 1;\n" - " " << baseTypeName << " * outLocal[1];\n" - " unsigned long " << indexIt << ";\n" - " unsigned long " << keyIndexName << ";\n" - " unsigned long e;\n"; - CPPADCG_ASSERT_UNKNOWN(indexIt != "e" && keyIndexName != "e"); - if (maxCompressedSize > 0) { - out << " " << baseTypeName << " compressed[" << maxCompressedSize << "];\n"; - } - out << " " << baseTypeName << " * " << resultName << " = out[0];\n" - "\n" - " inLocal[0] = in[0];\n" - " inLocal[1] = &inLocal1;\n"; - for (size_t j = 2; j < inLocalSize; j++) - out << " inLocal[" << j << "] = in[" << (j - 1) << "];\n"; - - out << "\n"; - - /** - * zero the output - */ - out << " for(e = 0; e < " << nnz << "; e++) " << resultName << "[e] = 0;\n" - "\n"; - - /** - * contributions from equations NOT belonging to loops - * (must come before the loop related values because of the assignments) - */ - langC.setArgumentIn("inLocal"); - langC.setArgumentOut("outLocal"); - string argsLocal = langC.generateDefaultFunctionArguments(); - - bool lastCompressed = false; - for (const auto& it : nonLoopElements) { - size_t index = it.first; - const set& elPos = it.second; - const std::vector >& location = matrixInfo.at(index).locations; - CPPADCG_ASSERT_UNKNOWN(elPos.size() <= location.size()); // it can be lower because not all elements have to be assigned - CPPADCG_ASSERT_UNKNOWN(elPos.size() > 0); - bool rowOrdered = matrixInfo.at(index).ordered; - - out << "\n"; - if (rowOrdered) { - out << " outLocal[0] = &" << resultName << "[" << *location[0].begin() << "];\n"; - } else if (!lastCompressed) { - out << " outLocal[0] = compressed;\n"; - } - out << " " << localFunction << "_" << nlRev2Suffix << index << "(" << argsLocal << ");\n"; - if (!rowOrdered) { - for (size_t e : elPos) { - out << " "; - for (size_t itl : location[e]) { - out << resultName << "[" << itl << "] += compressed[" << e << "];\n"; - } - } - } - lastCompressed = !rowOrdered; - } - - /** - * loop related values - */ - for (const auto& itItlg : loopCalls) { - size_t itCount = itItlg.first; - if (itCount > 1) { - lastCompressed = false; - out << " for(" << indexIt << " = 0; " << indexIt << " < " << itCount << "; " << indexIt << "++) {\n"; - } - - for (const auto& itlg : itItlg.second) { - LoopModel& loop = *itlg.first; - - for (const auto& itg : itlg.second) { - size_t g = itg.first; - ArrayGroup* group = itg.second; - - const map >& key2Compressed = loopGroups.at(&loop).at(g); - - string indent = itCount == 1 ? " " : " "; //indentation - - if (group->startLocPattern.get() != nullptr) { - // determine hessRowStart = f(it) - out << indent << "outLocal[0] = &" << resultName << "[" << LanguageC::indexPattern2String(*group->startLocPattern, indexIt) << "];\n"; - } else { - if (!lastCompressed) { - out << indent << "outLocal[0] = compressed;\n"; - } - out << indent << "for(e = 0; e < " << maxCompressedSize << "; e++) compressed[e] = 0;\n"; - } - - if (itCount > 1) { - out << indent << keyIndexName << " = " << LanguageC::indexPattern2String(*group->pattern, indexIt) << ";\n"; - out << indent; - (*generateLocalFunctionName)(out, modelName, loop, g); - out << "(" << keyIndexName << ", " << loopFArgs << ");\n"; - } else { - size_t key = key2Compressed.begin()->first; // only one jrow - out << indent; - (*generateLocalFunctionName)(out, modelName, loop, g); - out << "(" << key << ", " << loopFArgs << ");\n"; - } - - if (group->startLocPattern.get() == nullptr) { - CPPADCG_ASSERT_UNKNOWN(!group->elCount2elements.m.empty()); - - std::set usedIter; - - // add keys which are never used to usedIter to improve the if/else condition - size_t eKey = 0; - for (const auto& itKey : key2Compressed) { - size_t key = itKey.first; - for (size_t k = eKey; k < key; k++) { - usedIter.insert(k); - } - eKey = key + 1; - } - - bool withIfs = group->elCount2elements.size() > 1; - for (auto itc = group->elCount2elements.begin(); itc != group->elCount2elements.end(); ++itc) { - const ArrayElementGroup* eg = itc->second; - CPPADCG_ASSERT_UNKNOWN(!eg->elements.empty()); - - string indent2 = indent; - if (withIfs) { - out << indent; - if (itc != group->elCount2elements.begin()) - out << "} else "; - if (itc->first != group->elCount2elements.rbegin()->first) { // check that it is not the last branch - out << "if("; - - size_t maxKey = key2Compressed.rbegin()->first; - std::vector info = createIndexConditionExpression(eg->keys, usedIter, maxKey); - LanguageC::printIndexCondExpr(out, info, keyIndexName); - out << ") "; - - usedIter.insert(eg->keys.begin(), eg->keys.end()); - } - out << "{\n"; - indent2 += " "; - } - - for (size_t e = 0; e < eg->elements.size(); e++) { - const ArrayElementCopyPattern& ePos = eg->elements[e]; - - out << indent2 << resultName << "[" - << LanguageC::indexPattern2String(*ePos.resultPattern, indexIt) - << "] += compressed[" - << LanguageC::indexPattern2String(*ePos.compressedPattern, indexIt) - << "];\n"; - } - } - - if (withIfs) { - out << indent << "}\n"; - } - } - - out << "\n"; - - lastCompressed = group->startLocPattern.get() == nullptr; - } - } - - if (itCount > 1) { - out << " }\n"; - } - } - - out << "\n" - "}\n"; -} - -/** - * - * @param elements - * @param loopGroups Used elements from the arrays provided by the group - * function calls (loop->group->{array->{compressed position} }) - * @param nonLoopElements Used elements from non loop function calls - * ([array]{compressed position}) - * @param functionName - * @param modelName - * @param baseTypeName - * @param suffix - * @param generateLocalFunctionName - * @return - */ -template -std::string generateGlobalForRevWithLoopsFunctionSource(const std::map >& elements, - const std::map*, std::map > > >& loopGroups, - const std::map >& nonLoopElements, - const std::string& functionName, - const std::string& modelName, - const std::string& baseTypeName, - const std::string& suffix, - void (*generateLocalFunctionName)(std::ostringstream& cache, const std::string& modelName, const LoopModel& loop, size_t g)) { - - using namespace std; - - // functions for each row - map*, set > > functions; - - for (const auto& itlj1g : loopGroups) { - LoopModel* loop = itlj1g.first; - - for (const auto& itg : itlj1g.second) { - size_t group = itg.first; - const map >& jrows = itg.second; - - for (const auto& itJrow : jrows) { - functions[itJrow.first][loop].insert(group); - } - } - } - - /** - * The function that matches each equation to a directional derivative function - */ - LanguageC langC(baseTypeName); - string argsDcl = langC.generateDefaultFunctionArgumentsDcl(); - string args = langC.generateDefaultFunctionArguments(); - string noLoopFunc = functionName + "_noloop_" + suffix; - - std::ostringstream out; - out << LanguageC::ATOMICFUN_STRUCT_DEFINITION << "\n" - "\n"; - ModelCSourceGen::generateFunctionDeclarationSource(out, functionName, "noloop_" + suffix, nonLoopElements, argsDcl); - generateFunctionDeclarationSourceLoopForRev(out, langC, modelName, "j", loopGroups, generateLocalFunctionName); - out << "\n"; - out << "int " << functionName << - "(unsigned long pos, " << argsDcl << ") {\n" - " \n" - " switch(pos) {\n"; - - for (const auto& it : elements) { - size_t jrow = it.first; - // the size of each sparsity row - out << " case " << jrow << ":\n"; - - /** - * contributions from equations not in loops - * (must come before contributions from loops because of the assignments) - */ - const auto itnl = nonLoopElements.find(jrow); - if (itnl != nonLoopElements.end()) { - out << " " << noLoopFunc << jrow << "(" << args << ");\n"; - } - - /** - * contributions from equations in loops - */ - const map*, set >& rowFunctions = functions[jrow]; - - for (const auto& itlg : rowFunctions) { - LoopModel* loop = itlg.first; - - for (size_t itg : itlg.second) { - out << " "; - generateLocalFunctionName(out, modelName, *loop, itg); - out << "(" << jrow << ", " << args << ");\n"; - } - } - - /** - * return all OK - */ - out << " return 0; // done\n"; - } - out << " default:\n" - " return 1; // error\n" - " };\n"; - - out << "}\n"; - return out.str(); -} - -template -void generateFunctionDeclarationSourceLoopForRev(std::ostringstream& out, - LanguageC& langC, - const std::string& modelName, - const std::string& keyName, - const std::map*, std::map > > >& loopGroups, - void (*generateLocalFunctionName)(std::ostringstream& cache, const std::string& modelName, const LoopModel& loop, size_t g)) { - - std::string argsDcl = langC.generateFunctionArgumentsDcl(); - std::string argsDclLoop = "unsigned long " + keyName + ", " + argsDcl; - - for (const auto& itlg : loopGroups) { - const LoopModel& loop = *itlg.first; - - for (const auto& itg : itlg.second) { - size_t group = itg.first; - - out << "void "; - (*generateLocalFunctionName)(out, modelName, loop, group); - out << "(" << argsDclLoop << ");\n"; - } - } -} - -} // END loops namespace - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_for0.hpp b/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_for0.hpp deleted file mode 100644 index d19d6ce11..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_for0.hpp +++ /dev/null @@ -1,133 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_FOR0_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_FOR0_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/*************************************************************************** - * Methods related with loop insertion into the operation graph - **************************************************************************/ - -template -std::vector > ModelCSourceGen::prepareForward0WithLoops(CodeHandler& handler, - const std::vector& x) { - using namespace std; - using namespace loops; - - size_t m = _fun.Range(); - - std::vector y(m); - - // temporaries - std::vector tmps; - - /** - * original equations outside the loops - */ - if (_funNoLoops != nullptr) { - const std::vector& origEq = _funNoLoops->getOrigDependentIndexes(); - - std::vector depNL = _funNoLoops->getTape().Forward(0, x); - - // original equations - for (size_t e = 0; e < origEq.size(); e++) { - y[origEq[e]] = depNL[e]; - } - - tmps.resize(depNL.size() - origEq.size()); - for (size_t i = origEq.size(); i < depNL.size(); i++) - tmps[i - origEq.size()] = depNL[i]; - } - - /** - * equations in loops - */ - OperationNode* iterationIndexDcl = handler.makeIndexDclrNode(LoopModel::ITERATION_INDEX_NAME); - - for (LoopModel* itl : _loopTapes) { - LoopModel& lModel = *itl; - size_t nIterations = lModel.getIterationCount(); - const std::vector >& dependents = lModel.getDependentIndexes(); - - /** - * make the loop start - */ - LoopStartOperationNode* loopStart = handler.makeLoopStartNode(*iterationIndexDcl, nIterations); - - IndexOperationNode* iterationIndexOp = handler.makeIndexNode(*loopStart); - std::set*> indexesOps; - indexesOps.insert(iterationIndexOp); - - std::vector > ifElses; - - /** - * evaluate the loop body - */ - std::vector indexedIndeps = createIndexedIndependents(handler, lModel, *iterationIndexOp); - std::vector xl = createLoopIndependentVector(handler, lModel, indexedIndeps, x, tmps); - if (xl.size() == 0) { - xl.resize(1); // does not depend on any variable but CppAD requires at least one - xl[0] = Base(0); - } - std::vector yl = lModel.getTape().Forward(0, xl); - - /** - * make the loop end - */ - size_t assignOrAdd = 0; - - const std::vector& depPatterns = lModel.getDependentIndexPatterns(); - std::vector > indexedLoopResults(yl.size()); - for (size_t i = 0; i < yl.size(); i++) { - std::map locationsIter2Pos; - - for (size_t it = 0; it < nIterations; it++) { - if (dependents[i][it].original < m) { - locationsIter2Pos[it] = dependents[i][it].original; - } - } - - indexedLoopResults[i] = createLoopResult(handler, locationsIter2Pos, nIterations, - yl[i], depPatterns[i], assignOrAdd, - *iterationIndexOp, ifElses); - } - - LoopEndOperationNode* loopEnd = createLoopEnd(handler, *loopStart, indexedLoopResults, indexesOps, assignOrAdd); - - for (size_t i = 0; i < dependents.size(); i++) { - for (size_t it = 0; it < nIterations; it++) { - // an additional alias variable is required so that each dependent variable can have its own ID - size_t e = dependents[i][it].original; - if (e < m) { // some equations are not present in all iteration - y[e] = handler.createCG(*handler.makeNode(CGOpCode::DependentRefRhs,{e}, {*loopEnd})); - } - } - } - - /** - * move non-indexed expressions outside loop - */ - moveNonIndexedOutsideLoop(handler, *loopStart, *loopEnd); - } - - return y; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_for1.hpp b/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_for1.hpp deleted file mode 100644 index 848b653a0..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_for1.hpp +++ /dev/null @@ -1,930 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_FOR1_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_FOR1_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/*************************************************************************** - * Methods related with loop insertion into the operation graph - **************************************************************************/ - -template -void ModelCSourceGen::prepareSparseForwardOneWithLoops(const std::map >& elements) { - using namespace std; - using namespace CppAD::cg::loops; - //printSparsityPattern(_jacSparsity.rows, _jacSparsity.cols, "jacobian", _fun.Range()); - - size_t n = _fun.Domain(); - - CodeHandler handler; - handler.setJobTimer(_jobTimer); - handler.setZeroDependents(false); - - auto& indexJcolDcl = *handler.makeIndexDclrNode("jcol"); - auto& indexLocalItDcl = *handler.makeIndexDclrNode("it"); - auto& indexLocalItCountDcl = *handler.makeIndexDclrNode("itCount"); - auto& indexIterationDcl = *handler.makeIndexDclrNode(LoopModel::ITERATION_INDEX_NAME); - auto& iterationIndexOp = *handler.makeIndexNode(indexIterationDcl); - auto& jcolIndexOp = *handler.makeIndexNode(indexJcolDcl); - - std::vector*> localNodes(6); - localNodes[0] = &indexJcolDcl; - localNodes[1] = &indexLocalItDcl; - localNodes[2] = &indexLocalItCountDcl; - localNodes[3] = &indexIterationDcl; - localNodes[4] = &iterationIndexOp; - localNodes[5] = &jcolIndexOp; - - size_t nonIndexdedEqSize = _funNoLoops != nullptr ? _funNoLoops->getOrigDependentIndexes().size() : 0; - - std::vector > noLoopEvalSparsity; - std::vector > > noLoopEvalLocations; // tape equation -> original J -> locations - map*, std::vector > > loopsEvalSparsities; - map*, std::vector > loopEqInfo; - - size_t nnz = _jacSparsity.rows.size(); - std::vector rows(nnz); - std::vector cols(nnz); - std::vector locations(nnz); - - size_t p = 0; - for (const pair >& itJ : elements) {//loop variables - size_t j = itJ.first; - const std::vector& r = itJ.second; - - for (size_t e = 0; e < r.size(); e++) { // loop equations - rows[p] = r[e]; - cols[p] = j; - locations[p] = e; - p++; - } - } - CPPADCG_ASSERT_UNKNOWN(p == nnz); - - analyseSparseJacobianWithLoops(rows, cols, locations, - noLoopEvalSparsity, noLoopEvalLocations, loopsEvalSparsities, loopEqInfo); - - std::vector x(n); - handler.makeVariables(x); - if (_x.size() > 0) { - for (size_t i = 0; i < n; i++) { - x[i].setValue(_x[i]); - } - } - - CGBase dx; - handler.makeVariable(dx); - if (_x.size() > 0) { - dx.setValue(Base(1.0)); - } - - /*********************************************************************** - * generate the operation graph - **********************************************************************/ - - /** - * original equations outside the loops - */ - // temporaries (zero orders) - std::vector tmps; - - // Jacobian for temporaries - map > dzDx; - - /******************************************************************* - * equations NOT in loops - ******************************************************************/ - if (_funNoLoops != nullptr) { - ADFun& fun = _funNoLoops->getTape(); - - /** - * zero order - */ - std::vector depNL = _funNoLoops->getTape().Forward(0, x); - - tmps.resize(depNL.size() - nonIndexdedEqSize); - for (size_t i = 0; i < tmps.size(); i++) - tmps[i] = depNL[nonIndexdedEqSize + i]; - - /** - * Jacobian - */ - bool hasAtomics = isAtomicsUsed(); // TODO: improve this by checking only the current fun - map > dydxT = generateLoopFor1Jac(fun, - _funNoLoops->getJacobianSparsity(), - noLoopEvalSparsity, - x, hasAtomics); - - map > jacNl; // by column - for (const pair >& itDydxT : dydxT) { - size_t j = itDydxT.first; - const map& dydxjT = itDydxT.second; - - // prepare space for the Jacobian of the original equations - std::vector& col = jacNl[j]; - col.resize(elements.at(j).size()); - - for (const pair& itiv : dydxjT) { - size_t inl = itiv.first; - - if (inl < nonIndexdedEqSize) { - // (dy_i/dx_v) elements from equations outside loops - const set& locations = noLoopEvalLocations[inl][j]; - - CPPADCG_ASSERT_UNKNOWN(locations.size() == 1); // one Jacobian element should not be placed in several locations - size_t e = *locations.begin(); - - col[e] = itiv.second * dx; - - _nonLoopFor1Elements[j].insert(e); - } else { - // dz_k/dx_v (for temporary variable) - size_t k = inl - nonIndexdedEqSize; - dzDx[k][j] = itiv.second; - } - - } - } - - /** - * Create source for each variable present in equations outside loops - */ - typename map >::iterator itJ; - for (itJ = jacNl.begin(); itJ != jacNl.end(); ++itJ) { - size_t j = itJ->first; - if (_nonLoopFor1Elements.find(j) != _nonLoopFor1Elements.end()) // make sure there are elements - createForwardOneWithLoopsNL(handler, j, itJ->second); - } - } - - /*********************************************************************** - * equations in loops - **********************************************************************/ - typename map*, std::vector >::iterator itl2Eq; - for (itl2Eq = loopEqInfo.begin(); itl2Eq != loopEqInfo.end(); ++itl2Eq) { - LoopModel& lModel = *itl2Eq->first; - const std::vector& info = itl2Eq->second; - ADFun& fun = lModel.getTape(); - - //size_t nIndexed = lModel.getIndexedIndepIndexes().size(); - //size_t nNonIndexed = lModel.getNonIndexedIndepIndexes().size(); - - _cache.str(""); - _cache << "model (forward one, loop " << lModel.getLoopId() << ")"; - std::string jobName = _cache.str(); - - /** - * evaluate loop model Jacobian - */ - startingJob("'" + jobName + "'", JobTimer::GRAPH); - - std::vector indexedIndeps = createIndexedIndependents(handler, lModel, iterationIndexOp); - std::vector xl = createLoopIndependentVector(handler, lModel, indexedIndeps, x, tmps); - - bool hasAtomics = isAtomicsUsed(); // TODO: improve this by checking only the current fun - map > dyiDxtapeT = generateLoopFor1Jac(fun, - lModel.getJacobianSparsity(), - loopsEvalSparsities[&lModel], - xl, hasAtomics); - - finishedJob(); - - /******************************************************************* - * create Jacobian column groups - * for the contributions of the equations in loops - ******************************************************************/ - SmartVectorPointer > loopGroups; - - generateForOneColumnGroups(lModel, info, nnz, n, loopGroups); - - /******************************************************************* - * generate the operation graph for each Jacobian column subgroup - ******************************************************************/ - for (size_t g = 0; g < loopGroups.size(); g++) { - JacobianColGroup& group = *loopGroups[g]; - - /** - * determine if a loop should be created - */ - LoopStartOperationNode* loopStart = nullptr; - - map > localIterCount2Jcols; - - for (const pair >& itJcol2It : group.jCol2Iterations) { - size_t jcol = itJcol2It.first; - size_t itCount = itJcol2It.second.size(); - localIterCount2Jcols[itCount].insert(jcol); - } - - bool createsLoop = localIterCount2Jcols.size() != 1 || // is there a different number of iterations - localIterCount2Jcols.begin()->first != 1; // is there always just one iteration? - - /** - * Model index pattern - * - * detect the index pattern for the model iterations - * based on jcol and the local loop iteration - */ - map > jcol2localIt2ModelIt; - - for (const pair >& itJcol2It : group.jCol2Iterations) { - size_t jcol = itJcol2It.first; - - map& localIt2ModelIt = jcol2localIt2ModelIt[jcol]; - size_t localIt = 0; - set::const_iterator itIt; - for (itIt = itJcol2It.second.begin(); itIt != itJcol2It.second.end(); ++itIt, localIt++) { - localIt2ModelIt[localIt] = *itIt; - } - } - - /** - * try to fit a combination of two patterns: - * j = fStart(jcol) + flit(lit); - */ - std::unique_ptr itPattern(Plane2DIndexPattern::detectPlane2D(jcol2localIt2ModelIt)); - - if (itPattern.get() == nullptr) { - // did not match! - itPattern.reset(new Random2DIndexPattern(jcol2localIt2ModelIt)); - } - - /** - * Local iteration count pattern - */ - IndexOperationNode* localIterIndexOp = nullptr; - IndexOperationNode* localIterCountIndexOp = nullptr; - IndexAssignOperationNode* itCountAssignOp = nullptr; - std::unique_ptr indexLocalItCountPattern; - - if (createsLoop) { - map jcol2litCount; - - for (const pair >& itJcol2Its : group.jCol2Iterations) { - size_t jcol = itJcol2Its.first; - jcol2litCount[jcol] = itJcol2Its.second.size(); - } - - indexLocalItCountPattern.reset(IndexPattern::detect(jcol2litCount)); - - if (IndexPattern::isConstant(*indexLocalItCountPattern.get())) { - size_t itCount = group.jCol2Iterations.begin()->second.size(); - loopStart = handler.makeLoopStartNode(indexLocalItDcl, itCount); - } else { - itCountAssignOp = handler.makeIndexAssignNode(indexLocalItCountDcl, *indexLocalItCountPattern.get(), jcolIndexOp); - localIterCountIndexOp = handler.makeIndexNode(*itCountAssignOp); - loopStart = handler.makeLoopStartNode(indexLocalItDcl, *localIterCountIndexOp); - } - - localIterIndexOp = handler.makeIndexNode(*loopStart); - } - - - auto* iterationIndexPatternOp = handler.makeIndexAssignNode(indexIterationDcl, *itPattern.get(), &jcolIndexOp, localIterIndexOp); - iterationIndexOp.makeAssigmentDependent(*iterationIndexPatternOp); - - map > jcol2CompressedLoc; - std::vector, IndexPattern*> > indexedLoopResults; - - indexedLoopResults = generateForwardOneGroupOps(handler, lModel, info, - group, iterationIndexOp, - dx, dyiDxtapeT, dzDx, - jcol2CompressedLoc); - - _loopFor1Groups[&lModel][g] = jcol2CompressedLoc; - - LoopEndOperationNode* loopEnd = nullptr; - std::vector pxCustom; - if (createsLoop) { - /** - * make the loop end - */ - size_t assignOrAdd = 1; - set*> indexesOps; - indexesOps.insert(&iterationIndexOp); - loopEnd = createLoopEnd(handler, *loopStart, indexedLoopResults, indexesOps, assignOrAdd); - - /** - * move non-indexed expressions outside loop - */ - moveNonIndexedOutsideLoop(handler, *loopStart, *loopEnd); - - /** - * - */ - pxCustom.resize(1); - // {0} : must point to itself since there is only one dependent - pxCustom[0] = handler.createCG(*handler.makeNode(CGOpCode::DependentRefRhs,{0}, {*loopEnd})); - - } else { - /** - * No loop required - */ - pxCustom.resize(indexedLoopResults.size()); - for (size_t i = 0; i < indexedLoopResults.size(); i++) { - const CGBase& val = indexedLoopResults[i].first; - IndexPattern* ip = indexedLoopResults[i].second; - - pxCustom[i] = createLoopDependentFunctionResult(handler, i, val, ip, iterationIndexOp); - } - - } - - LanguageC langC(_baseTypeName); - langC.setFunctionIndexArgument(indexJcolDcl); - langC.setParameterPrecision(_parameterPrecision); - - _cache.str(""); - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("dy")); - LangCDefaultHessianVarNameGenerator nameGenHess(nameGen.get(), "dx", n); - - /** - * Generate the source code inside the loop - */ - _cache.str(""); - _cache << "model (forward one, loop " << lModel.getLoopId() << ", group " << g << ")"; - string jobName = _cache.str(); - handler.generateCode(code, langC, pxCustom, nameGenHess, _atomicFunctions, jobName); - - _cache.str(""); - generateFunctionNameLoopFor1(_cache, lModel, g); - std::string functionName = _cache.str(); - - std::string argsDcl = langC.generateFunctionArgumentsDcl(); - - _cache.str(""); - _cache << "#include \n" - "#include \n" - "\n" - << LanguageC::ATOMICFUN_STRUCT_DEFINITION << "\n" - "\n" - "void " << functionName << "(" << argsDcl << ") {\n"; - nameGenHess.customFunctionVariableDeclarations(_cache); - _cache << langC.generateIndependentVariableDeclaration() << "\n"; - _cache << langC.generateDependentVariableDeclaration() << "\n"; - _cache << langC.generateTemporaryVariableDeclaration(false, false, - handler.getExternalFuncMaxForwardOrder(), - handler.getExternalFuncMaxReverseOrder()) << "\n"; - nameGenHess.prepareCustomFunctionVariables(_cache); - - // code inside the loop - _cache << code.str(); - - nameGenHess.finalizeCustomFunctionVariables(_cache); - _cache << "}\n\n"; - - _sources[functionName + ".c"] = _cache.str(); - _cache.str(""); - - /** - * prepare the nodes to be reused! - */ - if (g + 1 < loopGroups.size()) { - handler.resetNodes(); // uncolor nodes - } - } - - } - - /** - * - */ - string functionFor1 = _name + "_" + FUNCTION_SPARSE_FORWARD_ONE; - _sources[functionFor1 + ".c"] = generateGlobalForRevWithLoopsFunctionSource(elements, - _loopFor1Groups, _nonLoopFor1Elements, - functionFor1, _name, _baseTypeName, "indep", - generateFunctionNameLoopFor1); - /** - * Sparsity - */ - _cache.str(""); - generateSparsity1DSource2(_name + "_" + FUNCTION_FORWARD_ONE_SPARSITY, elements); - _sources[_name + "_" + FUNCTION_FORWARD_ONE_SPARSITY + ".c"] = _cache.str(); - _cache.str(""); -} - -template -void ModelCSourceGen::createForwardOneWithLoopsNL(CodeHandler& handler, - size_t j, - std::vector >& jacCol) { - size_t n = _fun.Domain(); - - _cache.str(""); - _cache << "model (forward one, indep " << j << ") no loop"; - const std::string jobName = _cache.str(); - - LanguageC langC(_baseTypeName); - langC.setMaxAssigmentsPerFunction(_maxAssignPerFunc, &_sources); - langC.setParameterPrecision(_parameterPrecision); - _cache.str(""); - _cache << _name << "_" << FUNCTION_SPARSE_FORWARD_ONE << "_noloop_indep" << j; - langC.setGenerateFunction(_cache.str()); - - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("dy")); - LangCDefaultHessianVarNameGenerator nameGenHess(nameGen.get(), "dx", n); - - handler.generateCode(code, langC, jacCol, nameGenHess, _atomicFunctions, jobName); - - handler.resetNodes(); -} - - -namespace loops { - -/** - * Auxiliary structure - */ -struct Forward1Jcol2Iter { - size_t jcol; - std::set iterations; - - inline Forward1Jcol2Iter() { - } - - inline Forward1Jcol2Iter(size_t col, - const std::set& iters) : - jcol(col), - iterations(iters) { - } -}; - -inline bool operator<(const Forward1Jcol2Iter& l, const Forward1Jcol2Iter& r) { - if (l.jcol < r.jcol) - return true; - else if (l.jcol > r.jcol) - return false; - - return compare(l.iterations, r.iterations) == -1; -} - -/** - * Group of contributions to a Jacobian - */ -template -class JacobianTermContrib { -public: - std::set indexed; - std::set nonIndexed; // maximum one element -public: - - inline bool empty() const { - return indexed.empty() && nonIndexed.empty(); - } - - inline size_t size() const { - return indexed.size() + nonIndexed.size(); - } -}; - -template -bool operator<(const JacobianTermContrib& l, const JacobianTermContrib& r) { - int c = compare(l.indexed, r.indexed); - if (c != 0) return c == -1; - c = compare(l.nonIndexed, r.nonIndexed); - if (c != 0) return c == -1; - return false; -} - -/** - * Group of contributions to a Jacobian with the same relation between - * Jacobian columns and set of iterations - */ -template -class JacobianColGroup : public JacobianTermContrib { -public: - // all the required iterations for each jcol - std::map > jCol2Iterations; - // all iterations - std::set iterations; - // if-else branches - std::vector > ifElses; -public: - - inline JacobianColGroup(const JacobianTermContrib& c, - const Forward1Jcol2Iter& jcol2Iters) : - JacobianTermContrib(c), - iterations(jcol2Iters.iterations) { - jCol2Iterations[jcol2Iters.jcol] = jcol2Iters.iterations; - } -}; - -template -void generateForOneColumnGroups(const LoopModel& lModel, - const std::vector& loopEqInfo, - size_t max, - size_t n, - SmartVectorPointer >& loopGroups) { - using namespace std; - using namespace CppAD::cg::loops; - - /** - * group columns with the same contribution terms - */ - map > > indexed2jcol2Iter; - map > nonIndexed2Iter; - - map, set > contrib2jcols = groupForOneByContrib(lModel, loopEqInfo, - n, - indexed2jcol2Iter, - nonIndexed2Iter); - - loopGroups.reserve(contrib2jcols.size() * 2); // TODO: improve this - std::map, JacobianColGroup*> c2subgroups; - - for (const auto& itC : contrib2jcols) { - const JacobianTermContrib& c = itC.first; - const set& jcols = itC.second; - - /** - * create subgroups - */ - subgroupForOneByContrib(loopEqInfo, c, jcols, - indexed2jcol2Iter, nonIndexed2Iter, - loopGroups, c2subgroups); - } - -} - -/** - * Create groups with the same contributions at the same Jacobian columns - * - * @return maps each contribution group to the affected columns in the - * Jacobian - */ -template -std::map, std::set > groupForOneByContrib(const LoopModel& lModel, - const std::vector& loopEqInfo, - size_t n, - std::map > >& indexed2jcol2Iter, - std::map >& nonIndexed2Iter) { - - using namespace std; - - /** - * determine the contributions to each Jacobian column - */ - std::vector > jcols(n); - - size_t nIterations = lModel.getIterationCount(); - - const std::vector >& indexedIndepIndexes = lModel.getIndexedIndepIndexes(); - - for (size_t i = 0; i < loopEqInfo.size(); i++) { - const JacobianWithLoopsRowInfo& row = loopEqInfo[i]; - - // indexed - for (const pair >& it : row.indexedPositions) { - size_t tapeJ = it.first; - const std::vector& positions = it.second; - map >& jcol2Iter = indexed2jcol2Iter[tapeJ]; - - for (size_t iter = 0; iter < nIterations; iter++) { - // it is present in all iterations but the user might request fewer elements in the Jacobian - // (it may be because the equation might not exist for this iteration) - if (positions[iter] != std::numeric_limits::max()) { - size_t j = indexedIndepIndexes[tapeJ][iter].original; - jcols[j].indexed.insert(tapeJ); - jcol2Iter[j].insert(iter); - } - } - } - - // non-indexed - for (const pair >& it : row.nonIndexedPositions) { - size_t j = it.first; - const std::vector& positions = it.second; - set& jcol2Iter = nonIndexed2Iter[j]; - bool used = false; - - for (size_t iter = 0; iter < nIterations; iter++) { - // it is present in all iterations but the user might request fewer elements in the Jacobian - // (it may be because the equation might not exist for this iteration) - if (positions[iter] != std::numeric_limits::max()) { - used = true; - jcol2Iter.insert(iter); - } - } - if (used) { - jcols[j].nonIndexed.insert(j); - } - } - - } - - /** - * group columns with the same contribution terms - */ - map, set > contrib2jcols; - for (size_t j = 0; j < n; j++) { - if (!jcols[j].empty()) - contrib2jcols[jcols[j]].insert(j); - } - - return contrib2jcols; -} - -/** - * Create subgroups from groups with the same contributions at the - * same Jacobian columns. Each subgroup has a sub-set of the group's - * contributions which have the same relations between Jacobian column - * index and set of iteration indexes. - */ -template -inline void subgroupForOneByContrib(const std::vector& loopEqInfo, - const JacobianTermContrib& c, - const std::set& jcols, - const std::map > >& indexed2jcol2Iter, - const std::map >& nonIndexed2Iter, - SmartVectorPointer >& subGroups, - std::map, JacobianColGroup*>& c2subgroups) { - using namespace std; - - map > contribs; - - map >::const_iterator itJcol2Iter; - - // indexed - for (size_t tapeJ : c.indexed) { - map > jcol2Iters = filterBykeys(indexed2jcol2Iter.at(tapeJ), jcols); - for (itJcol2Iter = jcol2Iters.begin(); itJcol2Iter != jcol2Iters.end(); ++itJcol2Iter) { - Forward1Jcol2Iter k(itJcol2Iter->first, itJcol2Iter->second); - contribs[k].indexed.insert(tapeJ); - } - } - - // non-indexed - for (size_t j : c.nonIndexed) { - // probably present in all iterations but the user might request fewer elements in the Jacobian - // (it may be because the equation might not exist for this iteration) - const set& iters = nonIndexed2Iter.at(j); - Forward1Jcol2Iter k(j, iters); - contribs[k].nonIndexed.insert(j); - } - - /** - * - */ - for (const pair >& itK2C : contribs) { - const Forward1Jcol2Iter& jcol2Iters = itK2C.first; - const JacobianTermContrib& hc = itK2C.second; - - typename map, JacobianColGroup*>::const_iterator its = c2subgroups.find(hc); - if (its != c2subgroups.end()) { - JacobianColGroup* sg = its->second; - sg->jCol2Iterations[jcol2Iters.jcol] = jcol2Iters.iterations; - sg->iterations.insert(jcol2Iters.iterations.begin(), jcol2Iters.iterations.end()); - } else { - JacobianColGroup* sg = new JacobianColGroup(hc, jcol2Iters); - subGroups.push_back(sg); - c2subgroups[hc] = sg; - } - } -} - -template -std::vector, IndexPattern*> > generateForwardOneGroupOps(CodeHandler& handler, - const LoopModel& lModel, - const std::vector& info, - JacobianColGroup& group, - IndexOperationNode& iterationIndexOp, - const CG& dx, - const std::map > >& dyiDxtapeT, - const std::map > >& dzDx, - std::map >& jcol2CompressedLoc) { - using namespace std; - using namespace CppAD::cg::loops; - - typedef CG CGBase; - - const std::vector >& indexedIndepIndexes = lModel.getIndexedIndepIndexes(); - - size_t jacElSize = group.size(); - - std::vector > indexedLoopResults(jacElSize * info.size()); - size_t jacLE = 0; - - map iter2jcols; - - for (size_t tapeI = 0; tapeI < info.size(); tapeI++) { - const JacobianWithLoopsRowInfo& jlrw = info[tapeI]; - - /** - * indexed variable contributions - */ - // tape J index -> {locationIt0, locationIt1, ...} - for (size_t tapeJ : group.indexed) { - - map >::const_iterator itPos = jlrw.indexedPositions.find(tapeJ); - if (itPos != jlrw.indexedPositions.end()) { - const std::vector& positions = itPos->second; // compressed positions - - const std::vector& tapeJPos = indexedIndepIndexes[tapeJ]; - iter2jcols.clear(); - for (size_t iter : group.iterations) { - if (positions[iter] != std::numeric_limits::max()) { // the element must have been requested - CPPADCG_ASSERT_UNKNOWN(tapeJPos[iter].original != std::numeric_limits::max()); // the equation must exist for this iteration - iter2jcols[iter] = tapeJPos[iter].original; - } - } - - if (!iter2jcols.empty()) { - CGBase val = dyiDxtapeT.at(tapeJ).at(tapeI) * dx; - indexedLoopResults[jacLE++] = createForwardOneElement(handler, group, positions, iter2jcols, - val, iterationIndexOp, jcol2CompressedLoc); - } - } - } - - - /** - * non-indexed variable contributions - */ - // original J index -> {locationIt0, locationIt1, ...} - for (size_t j : group.nonIndexed) { - - map >::const_iterator itPos = jlrw.nonIndexedPositions.find(j); - if (itPos == jlrw.nonIndexedPositions.end()) { - continue; - } - const std::vector& positions = itPos->second; - - iter2jcols.clear(); - for (size_t iter : group.iterations) { - if (positions[iter] != std::numeric_limits::max()) {// the element must have been requested - CPPADCG_ASSERT_UNKNOWN(lModel.getDependentIndexes()[tapeI][iter].original != std::numeric_limits::max()); // the equation must exist for this iteration - iter2jcols[iter] = j; - } - } - if (!iter2jcols.empty()) { - - CGBase jacVal = Base(0); - - // non-indexed variables used directly - const LoopPosition* pos = lModel.getNonIndexedIndepIndexes(j); - if (pos != nullptr) { - size_t tapeJ = pos->tape; - - const map >& dyiDxJtapeT = dyiDxtapeT.at(tapeJ); - typename map::const_iterator itVal = dyiDxJtapeT.find(tapeI); - if (itVal != dyiDxJtapeT.end()) { - jacVal += itVal->second; - } - } - - // non-indexed variables used through temporary variables - map >::const_iterator itks = jlrw.tmpEvals.find(j); - if (itks != jlrw.tmpEvals.end()) { - const set& ks = itks->second; - for (size_t k : ks) { - size_t tapeJ = lModel.getTempIndepIndexes(k)->tape; - - jacVal += dyiDxtapeT.at(tapeJ).at(tapeI) * dzDx.at(k).at(j); - } - } - - CGBase val = jacVal * dx; - indexedLoopResults[jacLE++] = createForwardOneElement(handler, group, positions, iter2jcols, - val, iterationIndexOp, jcol2CompressedLoc); - } - } - } - - indexedLoopResults.resize(jacLE); - - return indexedLoopResults; -} - -template -std::pair, IndexPattern*> createForwardOneElement(CodeHandler& handler, - JacobianColGroup& group, - const std::vector& positions, - const std::map& iter2jcols, - const CG& dfdx, - IndexOperationNode& iterationIndexOp, - std::map >& jcol2CompressedLoc) { - using namespace std; - - /** - * Determine index pattern - */ - map locationsIter2Pos; - - for (const std::pair& itIt : iter2jcols) { - size_t iter = itIt.first; - size_t jcol = itIt.second; - CPPADCG_ASSERT_UNKNOWN(positions[iter] != std::numeric_limits::max()); - locationsIter2Pos[iter] = positions[iter]; - jcol2CompressedLoc[jcol].insert(positions[iter]); - } - - // generate the index pattern for the Jacobian compressed element - IndexPattern* pattern = IndexPattern::detect(locationsIter2Pos); - handler.manageLoopDependentIndexPattern(pattern); - - size_t assignOrAdd = 1; - return createLoopResult(handler, locationsIter2Pos, positions.size(), - dfdx, pattern, assignOrAdd, - iterationIndexOp, group.ifElses); -} - -} // END loops namespace - -template -std::map > > ModelCSourceGen::generateLoopFor1Jac(ADFun& fun, - const SparsitySetType& sparsity, - const SparsitySetType& evalSparsity, - const std::vector& x, - bool constainsAtomics) { - using namespace std; - - size_t n = fun.Domain(); - - map > dyDxT; - - if (!constainsAtomics) { - std::vector row, col; - generateSparsityIndexes(evalSparsity, row, col); - - if (row.size() == 0) - return dyDxT; // nothing to do - - std::vector jacLoop(row.size()); - - CppAD::sparse_jacobian_work work; // temporary structure for CppAD - fun.SparseJacobianForward(x, sparsity, row, col, jacLoop, work); - - // organize results - for (size_t el = 0; el < jacLoop.size(); el++) { - size_t i = row[el]; - size_t j = col[el]; - dyDxT[j][i] = jacLoop[el]; - } - - } else { - //transpose - std::vector > evalSparsityT(n); - transposePattern(evalSparsity, evalSparsityT); - - std::vector dx(n); - - for (size_t j = 0; j < n; j++) { - const set& column = evalSparsityT[j]; - - if (column.empty()) - continue; - - fun.Forward(0, x); - - dx[j] = Base(1); - std::vector dy = fun.Forward(1, dx); - CPPADCG_ASSERT_UNKNOWN(dy.size() == fun.Range()); - dx[j] = Base(0); - - map& dyDxJT = dyDxT[j]; - - for (size_t i : column) { - dyDxJT[i] = dy[i]; - } - } - - } - - return dyDxT; -} - -template -void ModelCSourceGen::generateFunctionNameLoopFor1(std::ostringstream& cache, - const LoopModel& loop, - size_t g) { - generateFunctionNameLoopFor1(cache, _name, loop, g); -} - -template -void ModelCSourceGen::generateFunctionNameLoopFor1(std::ostringstream& cache, - const std::string& modelName, - const LoopModel& loop, - size_t g) { - cache << modelName << "_" << FUNCTION_SPARSE_FORWARD_ONE << - "_loop" << loop.getLoopId() << "_g" << g; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_hess.hpp b/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_hess.hpp deleted file mode 100644 index 89ef077b2..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_hess.hpp +++ /dev/null @@ -1,1214 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_HESS_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_HESS_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -namespace loops { - -class HessianElement { -public: - size_t location; // location in the compressed hessian vector - size_t row; - unsigned short count; // number of times to be added to that location - - inline HessianElement() : - location(std::numeric_limits::max()), - row(std::numeric_limits::max()), - count(0) { - } - -}; - -template -std::pair, IndexPattern*> createHessianContribution(CodeHandler& handler, - const std::vector& positions, - const CG& ddfdxdx, - IndexOperationNode& iterationIndexOp, - std::vector >& ifElses); - -} // END loops namespace - -/*************************************************************************** - * Methods related with loop insertion into the operation graph - **************************************************************************/ - -template -void ModelCSourceGen::analyseSparseHessianWithLoops(const std::vector& lowerHessRows, - const std::vector& lowerHessCols, - const std::vector& lowerHessOrder, - std::vector >& noLoopEvalJacSparsity, - std::vector >& noLoopEvalHessSparsity, - std::vector > >& noLoopEvalHessLocations, - std::map*, loops::HessianWithLoopsInfo >& loopHessInfo, - bool useSymmetry) { - using namespace std; - using namespace CppAD::cg::loops; - - size_t nonIndexdedEqSize = _funNoLoops != nullptr ? _funNoLoops->getOrigDependentIndexes().size() : 0; - - /** - * determine sparsities - */ - for (LoopModel* l : _loopTapes) { - l->evalJacobianSparsity(); - l->evalHessianSparsity(); - } - - if (_funNoLoops != nullptr) { - _funNoLoops->evalJacobianSparsity(); - _funNoLoops->evalHessianSparsity(); - } - - size_t m = _fun.Range(); - size_t n = _fun.Domain(); - - size_t nnz = lowerHessRows.size(); - - noLoopEvalJacSparsity.resize(_funNoLoops != nullptr ? m : 0); - noLoopEvalHessSparsity.resize(_funNoLoops != nullptr ? n : 0); - noLoopEvalHessLocations.resize(noLoopEvalHessSparsity.size()); - - loopHessInfo.clear(); - for (LoopModel* loop : _loopTapes) { - HessianWithLoopsInfo& loopHessInfol = loopHessInfo[loop]; - loopHessInfol = HessianWithLoopsInfo(*loop); - - // initialize Hessian information structure - loopHessInfol.noLoopEvalHessTempsSparsity.resize(_funNoLoops != nullptr ? n : 0); - } - - /** - * Load locations in the compressed Hessian - * d d y_i - * d x_j2 d x_j1 - */ - for (size_t eh = 0; eh < nnz; eh++) { - size_t j1 = lowerHessRows[eh]; - size_t j2 = lowerHessCols[eh]; - size_t e = lowerHessOrder[eh]; - - if (_funNoLoops != nullptr) { - // considers only the pattern for the original equations and leaves out the temporaries - const std::vector >& dydxx = _funNoLoops->getHessianOrigEqsSparsity(); - if (dydxx.size() > 0) { - if (dydxx[j1].find(j2) != dydxx[j1].end()) { - /** - * Present in the equations outside the loops - */ - noLoopEvalHessSparsity[j1].insert(j2); - noLoopEvalHessLocations[j1][j2].insert(e); - } - } - } - - for (LoopModel* loop : _loopTapes) { - size_t nIter = loop->getIterationCount(); - - const std::vector >& eqGroups = loop->getEquationsGroups(); - const std::vector >& loopJac = loop->getJacobianSparsity(); - HessianWithLoopsInfo& loopInfo = loopHessInfo.at(loop); - - const std::vector >& indexedIndepIndexes = loop->getIndexedIndepIndexes(); - const std::vector& nonIndexedIndepIndexes = loop->getNonIndexedIndepIndexes(); - const std::vector& temporaryIndependents = loop->getTemporaryIndependents(); - - size_t nIndexed = indexedIndepIndexes.size(); - size_t nNonIndexed = nonIndexedIndepIndexes.size(); - - const LoopPosition* posJ1 = loop->getNonIndexedIndepIndexes(j1); - const LoopPosition* posJ2 = (j1 == j2) ? posJ1 : loop->getNonIndexedIndepIndexes(j2); - - size_t nEqGroups = loopInfo.equationGroups.size(); - - for (size_t g = 0; g < nEqGroups; g++) { - const IterEquationGroup& group = eqGroups[g]; - const std::vector >& groupHess = group.getHessianSparsity(); - - /** - * indexed - indexed - * d d f_i - * d x_l2 d x_l1 - */ - const std::vector >& iter2tapeJJ = group.getHessianIndexedIndexedTapeIndexes(j1, j2); - for (size_t iteration = 0; iteration < iter2tapeJJ.size(); iteration++) { - const set& tapePairs = iter2tapeJJ[iteration]; - - for (const pairss& itPairs : tapePairs) { - size_t tape1 = itPairs.first; - size_t tape2 = itPairs.second; - pairss tape; - if (useSymmetry && tape1 > tape2 && groupHess[tape2].find(tape1) != groupHess[tape2].end()) { - tape = pairss(tape2, tape1); // work the symmetry - } else { - tape = itPairs; - } - - std::vector& positions = loopInfo.equationGroups[g].indexedIndexedPositions[tape]; - positions.resize(nIter); - - positions[iteration].location = e; - positions[iteration].row = j1; - positions[iteration].count++; - - loopInfo.equationGroups[g].evalHessSparsity[tape.first].insert(tape.second); - } - } - - - /** - * indexed - non-indexed - * d d f_i -> d d f_i - * d x_j2 d x_l1 d x_l2 d x_j1 - */ - if (posJ2 != nullptr) { - - const std::vector >& iter2tapeJ1OrigJ2 = group.getHessianIndexedNonIndexedTapeIndexes(j1, j2); - for (size_t iteration = 0; iteration < iter2tapeJ1OrigJ2.size(); iteration++) { - const set& tapeJ1s = iter2tapeJ1OrigJ2[iteration]; - - for (size_t tapeJ1 : tapeJ1s) { - - bool flip = useSymmetry && groupHess[posJ2->tape].find(tapeJ1) != groupHess[posJ2->tape].end(); - - std::vector* positions; - if (flip) { - positions = &loopInfo.equationGroups[g].nonIndexedIndexedPositions[pairss(posJ2->tape, tapeJ1)]; - loopInfo.equationGroups[g].evalHessSparsity[posJ2->tape].insert(tapeJ1); - } else { - positions = &loopInfo.equationGroups[g].indexedNonIndexedPositions[pairss(tapeJ1, posJ2->tape)]; - loopInfo.equationGroups[g].evalHessSparsity[tapeJ1].insert(posJ2->tape); - } - - positions->resize(nIter); - (*positions)[iteration].location = e; - (*positions)[iteration].row = j1; - (*positions)[iteration].count++; - } - } - - } - } - - /** - * indexed - constant z - * d d f_i . d z_k - * d z_k d x_l1 d x_j2 - */ - if (_funNoLoops != nullptr) { - map > iter2tapeJ1 = loop->getIndexedTapeIndexes(j1); - for (const auto& itIter : iter2tapeJ1) { - size_t iteration = itIter.first; - const set& tapeJ1s = itIter.second; - const set*>& groups = loop->getIterationEquationsGroup()[iteration]; - - for (size_t tapeJ1 : tapeJ1s) { - for (const IterEquationGroup* itg : groups) { - const IterEquationGroup& group = *itg; - size_t g = group.index; - HessianWithLoopsEquationGroupInfo& groupInfo = loopInfo.equationGroups[g]; - const std::vector >& groupHess = group.getHessianSparsity(); - - set::const_iterator itz = groupHess[tapeJ1].lower_bound(nIndexed + nNonIndexed); - - pairss pos(tapeJ1, j2); - bool used = false; - - // loop temporary variables - for (; itz != groupHess[tapeJ1].end(); ++itz) { - size_t tapeJ = *itz; - size_t k = temporaryIndependents[tapeJ - nIndexed - nNonIndexed].original; - - /** - * check if this temporary depends on j2 - */ - const set& sparsity = _funNoLoops->getJacobianSparsity()[nonIndexdedEqSize + k]; - if (sparsity.find(j2) != sparsity.end()) { - noLoopEvalJacSparsity[nonIndexdedEqSize + k].insert(j2); // element required - - size_t tapeK = loop->getTempIndepIndexes(k)->tape; - - used = true; - - set& evals = groupInfo.indexedTempEvals[pos]; - evals.insert(k); - - groupInfo.evalHessSparsity[tapeJ1].insert(tapeK); - } - } - - - if (used) { - std::vector& positions = groupInfo.indexedTempPositions[pos]; - positions.resize(nIter); - - positions[iteration].location = e; - positions[iteration].row = j1; - positions[iteration].count++; - } - - } - - } - - } - } - - /** - * non-indexed - indexed - * d d f_i - * d x_l2 d x_j1 - */ - if (posJ1 != nullptr) { - - for (size_t g = 0; g < nEqGroups; g++) { - const IterEquationGroup& group = eqGroups[g]; - - const std::vector >& iter2TapeJ2 = group.getHessianNonIndexedIndexedTapeIndexes(j1, j2); - for (size_t iteration = 0; iteration < iter2TapeJ2.size(); iteration++) { - const set& tapeJ2s = iter2TapeJ2[iteration]; - - for (size_t tapeJ2 : tapeJ2s) { - std::vector& positions = loopInfo.equationGroups[g].nonIndexedIndexedPositions[pairss(posJ1->tape, tapeJ2)]; - positions.resize(nIter); - positions[iteration].location = e; - positions[iteration].row = j1; - positions[iteration].count++; - - loopInfo.equationGroups[g].evalHessSparsity[posJ1->tape].insert(tapeJ2); - } - } - } - } - - /** - * non-indexed - non-indexed - * d d f_i - * d x_j2 d x_j1 - */ - bool jInNonIndexed = false; - pairss orig(j1, j2); - - if (posJ1 != nullptr && posJ2 != nullptr) { - for (size_t g = 0; g < nEqGroups; g++) { - const IterEquationGroup& group = eqGroups[g]; - - const set& orig1orig2 = group.getHessianNonIndexedNonIndexedIndexes(); - if (orig1orig2.find(orig) != orig1orig2.end()) { - jInNonIndexed = true; - - loopInfo.equationGroups[g].nonIndexedNonIndexedEvals.insert(orig); - loopInfo.equationGroups[g].evalHessSparsity[posJ1->tape].insert(posJ2->tape); - } - - } - - if (jInNonIndexed) - loopInfo.nonIndexedNonIndexedPosition[orig] = e; - } - - /** - * non-indexed - temporaries - * d d f_i . d z_k - * d z_k d x_j1 d x_j2 - */ - if (_funNoLoops != nullptr && posJ1 != nullptr) { - - for (size_t g = 0; g < nEqGroups; g++) { - const IterEquationGroup& group = eqGroups[g]; - - const set& hessRow = group.getHessianSparsity()[posJ1->tape]; - set::const_iterator itz = hessRow.lower_bound(nIndexed + nNonIndexed); - - // loop temporary variables - for (; itz != hessRow.end(); ++itz) { - size_t tapeJ = *itz; - size_t k = temporaryIndependents[tapeJ - nIndexed - nNonIndexed].original; - - // Jacobian of g for k must have j2 - const set& gJacRow = _funNoLoops->getJacobianSparsity()[nonIndexdedEqSize + k]; - if (gJacRow.find(j2) != gJacRow.end()) { - noLoopEvalJacSparsity[nonIndexdedEqSize + k].insert(j2); // element required - - if (!jInNonIndexed) { - jInNonIndexed = true; - CPPADCG_ASSERT_KNOWN(loopInfo.nonIndexedNonIndexedPosition.find(orig) == loopInfo.nonIndexedNonIndexedPosition.end(), - "Repeated hessian elements requested"); - loopInfo.nonIndexedNonIndexedPosition[orig] = e; - } - - size_t tapeK = loop->getTempIndepIndexes(k)->tape; - loopInfo.equationGroups[g].nonIndexedTempEvals[orig].insert(k); - loopInfo.equationGroups[g].evalHessSparsity[posJ1->tape].insert(tapeK); - } - - } - } - } - - /** - * temporaries - */ - if (_funNoLoops != nullptr) { - const std::vector >& gJac = _funNoLoops->getJacobianSparsity(); - size_t nk = _funNoLoops->getTemporaryDependentCount(); - size_t nOrigEq = _funNoLoops->getTapeDependentCount() - nk; - - const std::vector >& dzdxx = _funNoLoops->getHessianTempEqsSparsity(); - - std::vector > usedTapeJ2(nEqGroups); - - for (size_t k1 = 0; k1 < nk; k1++) { - if (gJac[nOrigEq + k1].find(j1) == gJac[nOrigEq + k1].end()) { - continue; - } - - const LoopPosition* posK1 = loop->getTempIndepIndexes(k1); - if (posK1 == nullptr) { - continue; - } - - /** - * temporary - indexed - * d d f_i - * d x_l d z_k1 - */ - - for (size_t g = 0; g < nEqGroups; g++) { - const IterEquationGroup& group = eqGroups[g]; - const std::vector >& groupHess = group.getHessianSparsity(); - HessianWithLoopsEquationGroupInfo& groupHessInfo = loopInfo.equationGroups[g]; - - const map >& tapeJ22Iter = group.getHessianTempIndexedTapeIndexes(k1, j2); - for (const auto& ittj22iter : tapeJ22Iter) { - size_t tapeJ2 = ittj22iter.first; - const set& iterations = ittj22iter.second; - - bool used = usedTapeJ2[g].find(tapeJ2) != usedTapeJ2[g].end(); - bool added = false; - - for (size_t iteration : iterations) { - std::vector* positions = nullptr; - - bool flip = useSymmetry && groupHess[tapeJ2].find(posK1->tape) != groupHess[tapeJ2].end(); - if (flip) { - if (!used) { - pairss pos(tapeJ2, j1); - positions = &groupHessInfo.indexedTempPositions[pos]; - } - groupHessInfo.evalHessSparsity[tapeJ2].insert(posK1->tape); - } else { - if (!used) { - pairss pos(j1, tapeJ2); - positions = &groupHessInfo.tempIndexedPositions[pos]; - } - groupHessInfo.evalHessSparsity[posK1->tape].insert(tapeJ2); - } - - if (positions != nullptr) { - positions->resize(nIter); - - (*positions)[iteration].location = e; - (*positions)[iteration].row = j1; - (*positions)[iteration].count++; - usedTapeJ2[g].insert(tapeJ2); - } - - if (!added) { - added = true; - set& evals = groupHessInfo.indexedTempEvals[pairss(tapeJ2, j1)]; - evals.insert(k1); - } - } - - } - - /** - * temporary - non-indexed - * d d f_i - * d x_j2 d z_k1 - */ - if (posJ2 != nullptr) { - const set& hessRow = group.getHessianSparsity()[posK1->tape]; - - if (hessRow.find(j2) != hessRow.end()) { - if (!jInNonIndexed) { - jInNonIndexed = true; - CPPADCG_ASSERT_KNOWN(loopInfo.nonIndexedNonIndexedPosition.find(orig) == loopInfo.nonIndexedNonIndexedPosition.end(), - "Repeated hessian elements requested"); - loopInfo.nonIndexedNonIndexedPosition[orig] = e; - } - - groupHessInfo.tempNonIndexedEvals[orig].insert(k1); - groupHessInfo.evalHessSparsity[posK1->tape].insert(posJ2->tape); - } - } - - - /** - * temporary - temporary - * d d f_i . d z_k2 - * d z_k2 d z_k1 d x_j2 - */ - // loop Hessian row - const set& hessRow = group.getHessianSparsity()[posK1->tape]; - set::const_iterator itTapeJ2 = hessRow.lower_bound(nIndexed + nNonIndexed); - for (; itTapeJ2 != hessRow.end(); ++itTapeJ2) { - size_t tapeK2 = *itTapeJ2; - size_t k2 = loop->getTemporaryIndependents()[tapeK2 - nIndexed - nNonIndexed].original; - - const set& jacZk2Row = gJac[nOrigEq + k2]; - if (jacZk2Row.find(j2) != jacZk2Row.end()) { // is this check truly needed? - - if (!jInNonIndexed) { - jInNonIndexed = true; - CPPADCG_ASSERT_KNOWN(loopInfo.nonIndexedNonIndexedPosition.find(orig) == loopInfo.nonIndexedNonIndexedPosition.end(), - "Repeated hessian elements requested"); - loopInfo.nonIndexedNonIndexedPosition[orig] = e; - } - - groupHessInfo.tempTempEvals[orig][k1].insert(k2); - groupHessInfo.evalHessSparsity[posK1->tape].insert(tapeK2); - - noLoopEvalJacSparsity[nOrigEq + k2].insert(j2); // @todo: repeated operation for each group (only one needed) - } - } - } - - // - noLoopEvalJacSparsity[nOrigEq + k1].insert(j1); - - /** - * temporary - temporary - * d f_i . d d z_k1 - * d z_k1 d x_j2 d x_j1 - */ - if (dzdxx[j1].find(j2) != dzdxx[j1].end()) { - - for (size_t i = 0; i < loopJac.size(); i++) { - const set& fJacRow = loopJac[i]; - - if (fJacRow.find(posK1->tape) != fJacRow.end()) { - if (!jInNonIndexed) { - CPPADCG_ASSERT_KNOWN(loopInfo.nonIndexedNonIndexedPosition.find(orig) == loopInfo.nonIndexedNonIndexedPosition.end(), - "Repeated hessian elements requested"); - - loopInfo.nonIndexedNonIndexedPosition[orig] = e; - jInNonIndexed = true; - } - - loopInfo.nonLoopNonIndexedNonIndexed[orig].insert(k1); - loopInfo.evalJacSparsity[i].insert(posK1->tape); - loopInfo.noLoopEvalHessTempsSparsity[j1].insert(j2); - } - } - } - } - } - - } - } -} - -template -inline void addContribution(std::vector, IndexPattern*> >& indexedLoopResults, - size_t& hessLE, - const std::pair, IndexPattern*>& val) { - if (!val.first.isIdenticalZero()) { - if (indexedLoopResults.size() == hessLE) { - indexedLoopResults.resize(3 * hessLE / 2 + 1); - } - indexedLoopResults[hessLE++] = val; - } -} - -template -std::vector > ModelCSourceGen::prepareSparseHessianWithLoops(CodeHandler& handler, - std::vector& x, - std::vector& w, - const std::vector& lowerHessRows, - const std::vector& lowerHessCols, - const std::vector& lowerHessOrder, - const std::map& duplicates) { - using namespace std; - using namespace CppAD::cg::loops; - - handler.setZeroDependents(true); - - size_t nonIndexdedEqSize = _funNoLoops != nullptr ? _funNoLoops->getOrigDependentIndexes().size() : 0; - - size_t maxLoc = _hessSparsity.rows.size(); - std::vector hess(maxLoc); - - std::vector > noLoopEvalJacSparsity; - std::vector > noLoopEvalHessSparsity; - std::vector > > noLoopEvalHessLocations; - map*, HessianWithLoopsInfo > loopHessInfo; - - /** - * Load locations in the compressed Hessian - * d d y_i - * d x_j2 d x_j1 - */ - analyseSparseHessianWithLoops(lowerHessRows, lowerHessCols, lowerHessOrder, - noLoopEvalJacSparsity, noLoopEvalHessSparsity, - noLoopEvalHessLocations, loopHessInfo, true); - - /*********************************************************************** - * generate the operation graph - **********************************************************************/ - /** - * prepare loop independents - */ - OperationNode* iterationIndexDcl = handler.makeIndexDclrNode(LoopModel::ITERATION_INDEX_NAME); - - // temporaries (zero order) - std::vector tmpsAlias; - if (_funNoLoops != nullptr) { - ADFun& fun = _funNoLoops->getTape(); - - tmpsAlias.resize(fun.Range() - nonIndexdedEqSize); - for (size_t k = 0; k < tmpsAlias.size(); k++) { - // to be defined later - tmpsAlias[k] = CG(*handler.makeNode(CGOpCode::Alias)); - } - } - - /** - * prepare loop independents - */ - typename map*, HessianWithLoopsInfo >::iterator itLoop2Info; - for (itLoop2Info = loopHessInfo.begin(); itLoop2Info != loopHessInfo.end(); ++itLoop2Info) { - LoopModel& lModel = *itLoop2Info->first; - HessianWithLoopsInfo& info = itLoop2Info->second; - - /** - * make the loop start - */ - info.loopStart = handler.makeLoopStartNode(*iterationIndexDcl, lModel.getIterationCount()); - - info.iterationIndexOp = handler.makeIndexNode(*info.loopStart); - set*> indexesOps; - indexesOps.insert(info.iterationIndexOp); - - /** - * make the loop's indexed variables - */ - std::vector indexedIndeps = createIndexedIndependents(handler, lModel, *info.iterationIndexOp); - info.x = createLoopIndependentVector(handler, lModel, indexedIndeps, x, tmpsAlias); - - info.w = createLoopDependentVector(handler, lModel, *info.iterationIndexOp); - } - - /** - * Calculate Hessians and Jacobians - */ - /** - * Loops - evaluate Jacobian and Hessian - */ - for (itLoop2Info = loopHessInfo.begin(); itLoop2Info != loopHessInfo.end(); ++itLoop2Info) { - LoopModel& lModel = *itLoop2Info->first; - HessianWithLoopsInfo& info = itLoop2Info->second; - - _cache.str(""); - _cache << "model (Jacobian + Hessian, loop " << lModel.getLoopId() << ")"; - std::string jobName = _cache.str(); - _cache.str(""); - startingJob("'" + jobName + "'", JobTimer::GRAPH); - - info.evalLoopModelJacobianHessian(false); - - finishedJob(); - } - - /** - * No loops - */ - // Jacobian for temporaries - map > dzDx; - - if (_funNoLoops != nullptr) { - ADFun& fun = _funNoLoops->getTape(); - std::vector yNL(fun.Range()); - - /** - * Jacobian and Hessian - temporary variables - */ - startingJob("'model (Jacobian + Hessian, temporaries)'", JobTimer::GRAPH); - - dzDx = _funNoLoops->calculateJacobianHessianUsedByLoops(handler, - loopHessInfo, x, yNL, - noLoopEvalJacSparsity, - false); - - finishedJob(); - - for (size_t i = 0; i < tmpsAlias.size(); i++) - tmpsAlias[i].getOperationNode()->getArguments().push_back(asArgument(yNL[nonIndexdedEqSize + i])); - - for (itLoop2Info = loopHessInfo.begin(); itLoop2Info != loopHessInfo.end(); ++itLoop2Info) { - HessianWithLoopsInfo& info = itLoop2Info->second; - // not needed anymore: - info.dyiDzk.clear(); - } - - /** - * Hessian - original equations - */ - _funNoLoops->calculateHessian4OrignalEquations(x, w, - noLoopEvalHessSparsity, noLoopEvalHessLocations, - hess); - } - - /** - * Loops - Hessian - */ - for (itLoop2Info = loopHessInfo.begin(); itLoop2Info != loopHessInfo.end(); ++itLoop2Info) { - LoopModel& lModel = *itLoop2Info->first; - size_t nIterations = lModel.getIterationCount(); - HessianWithLoopsInfo& info = itLoop2Info->second; - - // store results in indexedLoopResults - size_t hessElSize = info.nonIndexedNonIndexedPosition.size(); - for (size_t g = 0; g < info.equationGroups.size(); g++) { - HessianWithLoopsEquationGroupInfo& infog = info.equationGroups[g]; - hessElSize += infog.indexedIndexedPositions.size() + - infog.indexedTempPositions.size() + - infog.nonIndexedIndexedPositions.size(); - } - - if (hessElSize == 0) - continue; // no second order information - - std::vector > indexedLoopResults(hessElSize); - size_t hessLE = 0; - - /** - * loop the groups of equations present at the same iterations - */ - for (size_t g = 0; g < info.equationGroups.size(); g++) { - - HessianWithLoopsEquationGroupInfo& infog = info.equationGroups[g]; - - /******************************************************************* - * indexed - indexed - */ - for (const auto& it : infog.indexedIndexedPositions) { - size_t tapeJ1 = it.first.first; - size_t tapeJ2 = it.first.second; - const std::vector& positions = it.second; - - addContribution(indexedLoopResults, hessLE, - createHessianContribution(handler, positions, infog.hess[tapeJ1].at(tapeJ2), - *info.iterationIndexOp, info.ifElses)); - } - - /** - * indexed - non-indexed - * - usually done by (non-indexed - indexed) by exploiting the symmetry - */ - for (const auto& it : infog.indexedNonIndexedPositions) { - size_t tapeJ1 = it.first.first; - size_t tapeJ2 = it.first.second; - const std::vector& positions = it.second; - - addContribution(indexedLoopResults, hessLE, - createHessianContribution(handler, positions, infog.hess[tapeJ1].at(tapeJ2), - *info.iterationIndexOp, info.ifElses)); - } - - /** - * indexed - temporary - */ - if (!infog.indexedTempPositions.empty()) { - for (const auto& itEval : infog.indexedTempEvals) { - size_t tapeJ1 = itEval.first.first; - size_t j2 = itEval.first.second; - const set& ks = itEval.second; - - const auto itPos = infog.indexedTempPositions.find(itEval.first); - if (itPos != infog.indexedTempPositions.end()) { - const std::vector& positions = itPos->second; - - CGBase hessVal = Base(0); - for (size_t k : ks) { - size_t tapeK = lModel.getTempIndepIndexes(k)->tape; - hessVal += infog.hess[tapeJ1].at(tapeK) * dzDx[k][j2]; - } - - addContribution(indexedLoopResults, hessLE, - createHessianContribution(handler, positions, hessVal, - *info.iterationIndexOp, info.ifElses)); - } - } - } - - /******************************************************************* - * non-indexed - indexed - */ - for (const auto& it : infog.nonIndexedIndexedPositions) { - size_t tapeJ1 = it.first.first; - size_t tapeJ2 = it.first.second; - const std::vector& positions = it.second; - - addContribution(indexedLoopResults, hessLE, - createHessianContribution(handler, positions, infog.hess[tapeJ1].at(tapeJ2), - *info.iterationIndexOp, info.ifElses)); - } - - /******************************************************************* - * temporary - indexed - * - * d f_i . d x_k1 - * d x_l2 d z_k1 d x_j1 - * - * -> usually done by (indexed - temporary) by exploiting the symmetry - */ - if (!infog.tempIndexedPositions.empty()) { - for (const auto& itEval : infog.indexedTempEvals) { - size_t tapeJ2 = itEval.first.first; - size_t j1 = itEval.first.second; - const set& ks = itEval.second; - - const auto itPos = infog.tempIndexedPositions.find(pairss(j1, tapeJ2)); - if (itPos != infog.tempIndexedPositions.end()) { - const std::vector& positions = itPos->second; - CGBase hessVal = Base(0); - for (size_t k : ks) { - size_t tapeK = lModel.getTempIndepIndexes(k)->tape; - hessVal += infog.hess[tapeK].at(tapeJ2) * dzDx[k][j1]; - } - - addContribution(indexedLoopResults, hessLE, - createHessianContribution(handler, positions, hessVal, - *info.iterationIndexOp, info.ifElses)); - } - } - } - - } - - /******************************************************************* - * contributions to a constant location - */ - for (const auto& orig2PosIt : info.nonIndexedNonIndexedPosition) { - const pairss& orig = orig2PosIt.first; - size_t e = orig2PosIt.second; - - size_t j1 = orig.first; - size_t j2 = orig.second; - const LoopPosition* posJ1 = lModel.getNonIndexedIndepIndexes(j1); - const LoopPosition* posJ2 = lModel.getNonIndexedIndepIndexes(j2); - - // location - LinearIndexPattern* pattern = new LinearIndexPattern(0, 0, 0, e); - handler.manageLoopDependentIndexPattern(pattern); - - /** - * non-indexed - non-indexed - */ - CGBase hessVal = Base(0); - - /** - * loop the groups of equations present at the same iterations - */ - for (size_t g = 0; g < info.equationGroups.size(); g++) { - const IterEquationGroup& group = lModel.getEquationsGroups()[g]; - - CGBase gHessVal = Base(0); - HessianWithLoopsEquationGroupInfo& infog = info.equationGroups[g]; - - if (infog.nonIndexedNonIndexedEvals.find(orig) != infog.nonIndexedNonIndexedEvals.end()) { - gHessVal = infog.hess[posJ1->tape].at(posJ2->tape); - } - - /** - * non-indexed - temporary - */ - const auto itNT = infog.nonIndexedTempEvals.find(orig); - if (itNT != infog.nonIndexedTempEvals.end()) { - const set& ks = itNT->second; - - for (size_t k : ks) { - size_t tapeK = lModel.getTempIndepIndexes(k)->tape; - gHessVal += infog.hess[posJ1->tape].at(tapeK) * dzDx[k][j2]; - } - } - - /** - * temporary - non-indexed - * - * d f_i . d x_k1 - * d x_j2 d z_k1 d x_j1 - */ - const auto itTN = infog.tempNonIndexedEvals.find(orig); - if (itTN != infog.tempNonIndexedEvals.end()) { - const set& ks = itTN->second; - - for (size_t k1 : ks) { - size_t tapeK = lModel.getTempIndepIndexes(k1)->tape; - gHessVal += infog.hess[tapeK].at(posJ2->tape) * dzDx[k1][j1]; - } - } - - /** - * temporary - temporary - */ - const auto itTT = infog.tempTempEvals.find(orig); - if (itTT != infog.tempTempEvals.end()) { - const map >& k1k2 = itTT->second; - - CGBase sum = Base(0); - - for (const auto& itzz : k1k2) { - size_t k1 = itzz.first; - const set& k2s = itzz.second; - size_t tapeK1 = lModel.getTempIndepIndexes(k1)->tape; - - CGBase tmp = Base(0); - for (size_t k2 : k2s) { - size_t tapeK2 = lModel.getTempIndepIndexes(k2)->tape; - - tmp += infog.hess[tapeK1].at(tapeK2) * dzDx[k2][j2]; - } - - sum += tmp * dzDx[k1][j1]; - } - - gHessVal += sum; - } - - if (group.iterations.size() != nIterations) { - CGBase v = createHessianContribution(handler, *pattern, group.iterations, - nIterations, gHessVal, - *info.iterationIndexOp, info.ifElses); - addContribution(indexedLoopResults, hessLE, make_pair(v, (IndexPattern*) nullptr)); - } else { - hessVal += gHessVal; - } - - } - - /** - * temporary - temporary - */ - const auto itTT2 = info.nonLoopNonIndexedNonIndexed.find(orig); - if (itTT2 != info.nonLoopNonIndexedNonIndexed.end()) { - hessVal += info.dzDxx.at(j1).at(j2); // it is already the sum of ddz / dx_j1 dx_j2 - } - - // place the result - addContribution(indexedLoopResults, hessLE, make_pair(hessVal, (IndexPattern*) pattern)); - } - - indexedLoopResults.resize(hessLE); - - /** - * make the loop end - */ - size_t assignOrAdd = 1; - set*> indexesOps; - indexesOps.insert(info.iterationIndexOp); - info.loopEnd = createLoopEnd(handler, *info.loopStart, indexedLoopResults, indexesOps, assignOrAdd); - - for (size_t e : lowerHessOrder) { - // an additional alias variable is required so that each dependent variable can have its own ID - if (hess[e].isIdenticalZero()) { - hess[e] = CG(*handler.makeNode(CGOpCode::DependentMultiAssign, *info.loopEnd)); - - } else if (hess[e].getOperationNode() != nullptr && hess[e].getOperationNode()->getOperationType() == CGOpCode::DependentMultiAssign) { - hess[e].getOperationNode()->getArguments().push_back(*info.loopEnd); - - } else { - hess[e] = handler.createCG(*handler.makeNode(CGOpCode::DependentMultiAssign,{asArgument(hess[e]), *info.loopEnd})); - } - } - - // not needed anymore: - for (size_t g = 0; g < info.equationGroups.size(); g++) { - info.equationGroups[g].hess.clear(); - } - info.dzDxx.clear(); - - /** - * move non-indexed expressions outside loop - */ - moveNonIndexedOutsideLoop(handler, *info.loopStart, *info.loopEnd); - } - - /** - * duplicates (TODO: use loops) - */ - // make use of the symmetry of the Hessian in order to reduce operations - for (const auto& it2 : duplicates) { - if (hess[it2.second].isVariable()) - hess[it2.first] = CG(*handler.makeNode(CGOpCode::Alias, asArgument(hess[it2.second]))); - else - hess[it2.first] = hess[it2.second].getValue(); - } - - return hess; -} - -namespace loops { - -template -std::pair, IndexPattern*> createHessianContribution(CodeHandler& handler, - const std::vector& positions, - const CG& ddfdxdx, - IndexOperationNode& iterationIndexOp, - std::vector >& ifElses) { - using namespace std; - - if (ddfdxdx.isIdenticalZero()) { - return make_pair(ddfdxdx, (IndexPattern*) nullptr); - } - - // combine iterations with the same number of additions - map > locations; - for (size_t iter = 0; iter < positions.size(); iter++) { - size_t c = positions[iter].count; - if (c > 0) { - locations[c][iter] = positions[iter].location; - } - } - - map > results; - - // generate the index pattern for the Hessian compressed element - for (const auto& countIt : locations) { - size_t count = countIt.first; - - CG val = ddfdxdx; - for (size_t c = 1; c < count; c++) - val += ddfdxdx; - - results[count] = val; - } - - if (results.size() == 1 && locations.begin()->second.size() == positions.size()) { - // same expression present in all iterations - - // generate the index pattern for the Hessian compressed element - IndexPattern* pattern = IndexPattern::detect(locations.begin()->second); - handler.manageLoopDependentIndexPattern(pattern); - - return make_pair(results.begin()->second, pattern); - - } else { - /** - * must create a conditional element so that this - * contribution to the Hessian is only evaluated at the - * relevant iterations - */ - map > branches; - - // try to find an existing if-else where these operations can be added - for (const auto& countIt : locations) { - - size_t count = countIt.first; - IfBranchData branch(results[count], countIt.second); - branches[count] = branch; - } - - CG v = createConditionalContribution(handler, - branches, - positions.size() - 1, - positions.size(), - iterationIndexOp, - ifElses); - - return make_pair(v, (IndexPattern*) nullptr); - } - -} - -/** - * Hessian contribution to a constant location - */ -template -CG createHessianContribution(CodeHandler& handler, - LinearIndexPattern& pattern, - const std::set& iterations, - size_t nIterations, - const CG& ddfdxdx, - IndexOperationNode& iterationIndexOp, - std::vector >& ifElses) { - using namespace std; - - if (ddfdxdx.isIdenticalZero()) { - return ddfdxdx; - } - - CPPADCG_ASSERT_UNKNOWN(pattern.getLinearSlopeDy() == 0); // must be a constant index - - if (iterations.size() == nIterations) { - // same expression present in all iterations - return ddfdxdx; - - } else { - - /** - * must create a conditional element so that this - * contribution to the Hessian is only evaluated at the - * relevant iterations - */ - return createConditionalContribution(handler, pattern, - iterations, nIterations - 1, - ddfdxdx, iterationIndexOp, - ifElses); - } -} - -template -inline void generateLoopForJacHes(ADFun >& fun, - const std::vector >& x, - const std::vector > >& vw, - std::vector >& y, - const std::vector >& jacSparsity, - const std::vector >& jacEvalSparsity, - std::vector > >& jac, - const std::vector >& hesSparsity, - const std::vector >& hesEvalSparsity, - std::vector > > >& vhess, - bool individualColoring) { - using namespace std; - - typedef CG CGB; - - size_t m = fun.Range(); - size_t n = fun.Domain(); - - jac.resize(m); - vhess.resize(vw.size()); - - if (!individualColoring) { - /** - * No atomics - */ - - // Jacobian for temporaries - std::vector jacRow, jacCol; - generateSparsityIndexes(jacEvalSparsity, jacRow, jacCol); - - // Jacobian for equations outside loops - std::vector jacFlat(jacRow.size()); - - /** - * Hessian - temporary variables - */ - std::vector hesRow, hesCol; - generateSparsityIndexes(hesEvalSparsity, hesRow, hesCol); - - std::vector > vhessFlat(vw.size()); - for (size_t l = 0; l < vw.size(); l++) { - vhessFlat[l].resize(hesRow.size()); - } - - std::vector > xl; - if (x.size() == 0) { - xl.resize(1); // does not depend on any variable but CppAD requires at least one - xl[0] = Base(0); - } else { - xl = x; - } - - SparseForjacHessianWork work; - sparseForJacHessian(fun, xl, vw, - y, - jacSparsity, - jacRow, jacCol, jacFlat, - hesSparsity, - hesRow, hesCol, vhessFlat, - work); - - // save Jacobian - for (size_t el = 0; el < jacRow.size(); el++) { - size_t i = jacRow[el]; - size_t j = jacCol[el]; - - jac[i][j] = jacFlat[el]; - } - - // save Hessian - for (size_t l = 0; l < vw.size(); l++) { - std::vector& hessFlat = vhessFlat[l]; - map >& hess = vhess[l]; - - for (size_t el = 0; el < hesRow.size(); el++) { - size_t j1 = hesRow[el]; - size_t j2 = hesCol[el]; - hess[j1][j2] = hessFlat[el]; - } - } - - } else { - /** - * Contains atomics - */ - - //transpose - std::vector > jacEvalSparsityT(n); - transposePattern(jacEvalSparsity, jacEvalSparsityT); - - std::vector tx1v(n); - - y = fun.Forward(0, x); - - for (size_t j1 = 0; j1 < n; j1++) { - if (jacEvalSparsityT[j1].empty() && hesEvalSparsity[j1].empty()) { - continue; - } - - tx1v[j1] = Base(1); - std::vector dy = fun.Forward(1, tx1v); - CPPADCG_ASSERT_UNKNOWN(dy.size() == m); - tx1v[j1] = Base(0); - - // save Jacobian - const set& column = jacEvalSparsityT[j1]; - for (size_t i : column) { - jac[i][j1] = dy[i]; - } - - const set& hesRow = hesEvalSparsity[j1]; - - if (!hesRow.empty()) { - - for (size_t l = 0; l < vw.size(); l++) { - - std::vector px = fun.Reverse(2, vw[l]); - CPPADCG_ASSERT_UNKNOWN(px.size() == 2 * n); - - // save Hessian - map& hessRow = vhess[l][j1]; - for (size_t j2 : hesRow) { - hessRow[j2] = px[j2 * 2 + 1]; - } - } - } - } - } - -} - -} // END loops namespace - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_hess_r2.hpp b/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_hess_r2.hpp deleted file mode 100644 index 1b8b08714..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_hess_r2.hpp +++ /dev/null @@ -1,67 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_HESS_R2_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_HESS_R2_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -void ModelCSourceGen::generateSparseHessianWithLoopsSourceFromRev2(const std::map& hessInfo, - size_t maxCompressedSize) { - using namespace std; - using namespace CppAD::cg::loops; - - startingJob("'sparse Hessian'", JobTimer::SOURCE_GENERATION); - - /** - * Generate the source code - */ - LanguageC langC(_baseTypeName); - string argsDcl = langC.generateDefaultFunctionArgumentsDcl(); - - string model_function = _name + "_" + FUNCTION_SPARSE_HESSIAN; - string functionRev2 = _name + "_" + FUNCTION_SPARSE_REVERSE_TWO; - string suffix = "indep"; - string nlRev2Suffix = "noloop_" + suffix; - - _cache.str(""); - _cache << "#include \n" - << LanguageC::ATOMICFUN_STRUCT_DEFINITION << "\n\n"; - generateFunctionDeclarationSource(_cache, functionRev2, nlRev2Suffix, _nonLoopRev2Elements, argsDcl); - generateFunctionDeclarationSourceLoopForRev(_cache, langC, _name, "jrow", _loopRev2Groups, generateFunctionNameLoopRev2); - - _cache << "\n"; - - printForRevUsageFunction(_cache, _baseTypeName, _name, - model_function, 3, - functionRev2, suffix, - "jrow", "it", "hess", - _loopRev2Groups, - _nonLoopRev2Elements, - hessInfo, - generateFunctionNameLoopRev2, - _hessSparsity.rows.size(), maxCompressedSize); - - finishedJob(); - - _sources[model_function + ".c"] = _cache.str(); - _cache.str(""); -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_jac.hpp b/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_jac.hpp deleted file mode 100644 index fb4a55d6f..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_jac.hpp +++ /dev/null @@ -1,526 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_JAC_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_JAC_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -namespace loops { - -template -std::pair, IndexPattern*> createJacobianElement(CodeHandler& handler, - const std::vector& positions, - const CG& dfdx, - IndexOperationNode& iterationIndexOp, - std::vector >& ifElses, - std::set& allLocations); - -} // END loops namespace - -/*************************************************************************** - * Methods related with loop insertion into the operation graph - **************************************************************************/ - -template -void ModelCSourceGen::analyseSparseJacobianWithLoops(const std::vector& rows, - const std::vector& cols, - const std::vector& location, - std::vector >& noLoopEvalSparsity, - std::vector > >& noLoopEvalLocations, - std::map*, std::vector > >& loopsEvalSparsities, - std::map*, std::vector >& loopEqInfo) { - - using namespace std; - using namespace loops; - - CPPADCG_ASSERT_UNKNOWN(rows.size() == cols.size()); - CPPADCG_ASSERT_UNKNOWN(rows.size() == location.size()); - - /** - * determine sparsities - */ - for (LoopModel* l : _loopTapes) { - l->evalJacobianSparsity(); - } - - if (_funNoLoops != nullptr) - _funNoLoops->evalJacobianSparsity(); - - /** - * Generate index patterns for the Jacobian elements resulting from loops - */ - size_t nonIndexdedEqSize = _funNoLoops != nullptr ? _funNoLoops->getOrigDependentIndexes().size() : 0; - noLoopEvalSparsity.resize(_funNoLoops != nullptr ? _funNoLoops->getTapeDependentCount() : 0); - - // tape equation -> original J -> locations - noLoopEvalLocations.resize(noLoopEvalSparsity.size()); - - // loop -> equation -> row info - for (LoopModel* loop : _loopTapes) { - loopEqInfo[loop].resize(loop->getTapeDependentCount()); - loopsEvalSparsities[loop].resize(loop->getTapeDependentCount()); - } - - size_t nnz = rows.size(); - - /** - * Load locations in the compressed Jacobian - */ - for (size_t el = 0; el < nnz; el++) { - size_t i = rows[el]; - size_t j = cols[el]; - size_t e = location[el]; - - // find LOOP + get loop results - LoopModel* loop = nullptr; - - size_t tapeI; - size_t iteration; - - for (LoopModel* l : _loopTapes) { - const std::map& depIndexes = l->getOriginalDependentIndexes(); - const auto iti = depIndexes.find(i); - if (iti != depIndexes.end()) { - loop = l; - tapeI = iti->second.tape; - iteration = iti->second.iteration; - break; - } - } - - if (loop == nullptr) { - /** - * Equation present in the model without loops - */ - CPPADCG_ASSERT_UNKNOWN(_funNoLoops != nullptr); - size_t il = _funNoLoops->getLocalDependentIndex(i); - - noLoopEvalSparsity[il].insert(j); - noLoopEvalLocations[il][j].insert(e); - - } else { - /** - * Equation belongs to a loop - */ - size_t iterations = loop->getIterationCount(); - - const std::vector >& indexedIndepIndexes = loop->getIndexedIndepIndexes(); - const std::vector& nonIndexedIndepIndexes = loop->getNonIndexedIndepIndexes(); - const std::vector& temporaryIndependents = loop->getTemporaryIndependents(); - - size_t nIndexed = indexedIndepIndexes.size(); - size_t nNonIndexed = nonIndexedIndepIndexes.size(); - - const std::vector >& loopSparsity = loop->getJacobianSparsity(); - const std::set& loopRow = loopSparsity[tapeI]; - - JacobianWithLoopsRowInfo& rowInfo = loopEqInfo[loop][tapeI]; - - std::set& loopEvalRow = loopsEvalSparsities[loop][tapeI]; - - /** - * find if there are indexed variables in this equation pattern - * and iteration which use j - */ - const std::set& tapeJs = loop->getIndexedTapeIndexes(iteration, j); - for (size_t tapeJ : tapeJs) { - if (loopRow.find(tapeJ) != loopRow.end()) { - loopEvalRow.insert(tapeJ); - - //this indexed variable must be request for all iterations - std::vector& positions = rowInfo.indexedPositions[tapeJ]; - positions.resize(iterations, std::numeric_limits::max()); - if (positions[iteration] != std::numeric_limits::max()) { - throw CGException("Repeated Jacobian elements requested (equation ", i, ", variable ", j, ")"); - } - positions[iteration] = e; - } - } - - /** - * find if there is a non indexed variable in this equation pattern for j - */ - const LoopPosition* pos = loop->getNonIndexedIndepIndexes(j); - bool jInNonIndexed = false; - if (pos != nullptr && loopRow.find(pos->tape) != loopRow.end()) { - loopEvalRow.insert(pos->tape); - - //this non-indexed element must be request for all iterations - std::vector& positions = rowInfo.nonIndexedPositions[j]; - positions.resize(iterations, std::numeric_limits::max()); - if (positions[iteration] != std::numeric_limits::max()) { - throw CGException("Repeated Jacobian elements requested (equation ", i, ", variable ", j, ")"); - } - positions[iteration] = e; - - rowInfo.nonIndexedEvals.insert(j); - - jInNonIndexed = true; - } - - /** - * find temporary variables used by this equation pattern - */ - if (_funNoLoops != nullptr) { - set::const_iterator itz = loopRow.lower_bound(nIndexed + nNonIndexed); - - // loop temporary variables - for (; itz != loopRow.end(); ++itz) { - size_t tapeJ = *itz; - size_t k = temporaryIndependents[tapeJ - nIndexed - nNonIndexed].original; - - /** - * check if this temporary depends on j - */ - bool used = false; - const set& sparsity = _funNoLoops->getJacobianSparsity()[nonIndexdedEqSize + k]; - if (sparsity.find(j) != sparsity.end()) { - noLoopEvalSparsity[nonIndexdedEqSize + k].insert(j); // element required - if (!jInNonIndexed) { - std::vector& positions = rowInfo.nonIndexedPositions[j]; - positions.resize(iterations, std::numeric_limits::max()); - if (positions[iteration] != std::numeric_limits::max()) { - throw CGException("Repeated Jacobian elements requested (equation ", i, ", variable ", j, ")"); - } - positions[iteration] = e; - jInNonIndexed = true; - } - rowInfo.tmpEvals[j].insert(k); - used = true; - } - - if (used) { - // this temporary variable should be evaluated - loopEvalRow.insert(tapeJ); - } - } - } - - } - } -} - -template -std::vector > ModelCSourceGen::prepareSparseJacobianWithLoops(CodeHandler& handler, - const std::vector& x, - bool forward) { - using namespace std; - using namespace CppAD::cg::loops; - //printSparsityPattern(_jacSparsity.rows, _jacSparsity.cols, "jacobian", _fun->Range()); - - handler.setZeroDependents(true); - - size_t nonIndexdedEqSize = _funNoLoops != nullptr ? _funNoLoops->getOrigDependentIndexes().size() : 0; - - std::vector > noLoopEvalSparsity; - std::vector > > noLoopEvalLocations; // tape equation -> original J -> locations - map*, std::vector > > loopsEvalSparsities; - map*, std::vector > loopEqInfo; - - size_t nnz = _jacSparsity.rows.size(); - std::vector locations(nnz); - for (size_t e = 0; e < nnz; e++) - locations[e] = e; - - analyseSparseJacobianWithLoops(_jacSparsity.rows, _jacSparsity.cols, locations, - noLoopEvalSparsity, noLoopEvalLocations, loopsEvalSparsities, loopEqInfo); - - - std::vector jac(nnz); - - /*********************************************************************** - * generate the operation graph - **********************************************************************/ - - /** - * original equations outside the loops - */ - // temporaries (zero orders) - std::vector tmps; - - // Jacobian for temporaries - std::vector > dzDx(_funNoLoops != nullptr ? _funNoLoops->getTemporaryDependentCount() : 0); - - // Jacobian for equations outside loops - std::vector jacNoLoop; - if (_funNoLoops != nullptr) { - ADFun& fun = _funNoLoops->getTape(); - - /** - * zero order - */ - std::vector depNL = _funNoLoops->getTape().Forward(0, x); - - tmps.resize(depNL.size() - nonIndexdedEqSize); - for (size_t i = 0; i < tmps.size(); i++) - tmps[i] = depNL[nonIndexdedEqSize + i]; - - /** - * Jacobian - */ - std::vector row, col; - generateSparsityIndexes(noLoopEvalSparsity, row, col); - jacNoLoop.resize(row.size()); - - CppAD::sparse_jacobian_work work; // temporary structure for CPPAD - if (forward) { - fun.SparseJacobianForward(x, _funNoLoops->getJacobianSparsity(), row, col, jacNoLoop, work); - } else { - fun.SparseJacobianReverse(x, _funNoLoops->getJacobianSparsity(), row, col, jacNoLoop, work); - } - - for (size_t el = 0; el < row.size(); el++) { - size_t il = row[el]; - size_t j = col[el]; - if (il < nonIndexdedEqSize) { - // (dy_i/dx_v) elements from equations outside loops - const std::set& locations = noLoopEvalLocations[il][j]; - for (size_t itE : locations) - jac[itE] = jacNoLoop[el]; - } else { - // dz_k/dx_v (for temporary variable) - size_t k = il - nonIndexdedEqSize; - dzDx[k][j] = jacNoLoop[el]; - } - } - } - - /*********************************************************************** - * Generate loop body - **********************************************************************/ - OperationNode* iterationIndexDcl = handler.makeIndexDclrNode(LoopModel::ITERATION_INDEX_NAME); - - std::vector jacLoop; - - // loop loops :) - typename map*, std::vector >::iterator itl2Eq; - for (itl2Eq = loopEqInfo.begin(); itl2Eq != loopEqInfo.end(); ++itl2Eq) { - LoopModel& lModel = *itl2Eq->first; - std::vector& eqs = itl2Eq->second; - ADFun& fun = lModel.getTape(); - - std::vector > ifElses; - - /** - * make the loop start - */ - LoopStartOperationNode* loopStart = handler.makeLoopStartNode(*iterationIndexDcl, lModel.getIterationCount()); - - IndexOperationNode* iterationIndexOp = handler.makeIndexNode(*loopStart); - std::set*> indexesOps; - indexesOps.insert(iterationIndexOp); - - /** - * evaluate loop model Jacobian - */ - std::vector indexedIndeps = createIndexedIndependents(handler, lModel, *iterationIndexOp); - std::vector xl = createLoopIndependentVector(handler, lModel, indexedIndeps, x, tmps); - - std::vector row, col; - generateSparsityIndexes(loopsEvalSparsities[&lModel], row, col); - jacLoop.resize(row.size()); - - if (row.size() == 0) { - continue; - } - - CppAD::sparse_jacobian_work work; // temporary structure for CppAD - if (forward) { - fun.SparseJacobianForward(xl, lModel.getJacobianSparsity(), row, col, jacLoop, work); - } else { - fun.SparseJacobianReverse(xl, lModel.getJacobianSparsity(), row, col, jacLoop, work); - } - - // organize results - std::vector > dyiDxtape(lModel.getTapeDependentCount()); - for (size_t el = 0; el < jacLoop.size(); el++) { - size_t tapeI = row[el]; - size_t tapeJ = col[el]; - dyiDxtape[tapeI][tapeJ] = jacLoop[el]; - } - - // all assigned elements in the compressed Jacobian by this loop - std::set allLocations; - - // store results in indexedLoopResults - size_t maxJacElSize = 0; - for (size_t tapeI = 0; tapeI < eqs.size(); tapeI++) { - JacobianWithLoopsRowInfo& rowInfo = eqs[tapeI]; - maxJacElSize += rowInfo.indexedPositions.size(); - maxJacElSize += rowInfo.nonIndexedPositions.size(); - } - - std::vector > indexedLoopResults(maxJacElSize); - - // create the dependents (jac elements) for indexed and constant - size_t jacLE = 0; - for (size_t tapeI = 0; tapeI < eqs.size(); tapeI++) { - JacobianWithLoopsRowInfo& rowInfo = eqs[tapeI]; - - prepareSparseJacobianRowWithLoops(handler, lModel, - tapeI, rowInfo, - dyiDxtape, dzDx, - CGBase(1), - *iterationIndexOp, ifElses, - jacLE, indexedLoopResults, allLocations); - } - - indexedLoopResults.resize(jacLE); - - /** - * make the loop end - */ - size_t assignOrAdd = 1; - LoopEndOperationNode* loopEnd = createLoopEnd(handler, *loopStart, indexedLoopResults, indexesOps, assignOrAdd); - - for (size_t e : allLocations) { - // an additional alias variable is required so that each dependent variable can have its own ID - jac[e] = handler.createCG(*handler.makeNode(CGOpCode::DependentRefRhs,{e}, {*loopEnd})); - } - - /** - * move non-indexed expressions outside loop - */ - moveNonIndexedOutsideLoop(handler, *loopStart, *loopEnd); - } - - return jac; -} - -template -void ModelCSourceGen::prepareSparseJacobianRowWithLoops(CodeHandler& handler, - LoopModel& lModel, - size_t tapeI, - const loops::JacobianWithLoopsRowInfo& rowInfo, - const std::vector >& dyiDxtape, - const std::vector >& dzDx, - const CGBase& py, - IndexOperationNode& iterationIndexOp, - std::vector >& ifElses, - size_t& jacLE, - std::vector, IndexPattern*> >& indexedLoopResults, - std::set& allLocations) { - using namespace std; - using namespace loops; - - /** - * indexed variable contributions - */ - // tape J index -> {locationIt0, locationIt1, ...} - for (const auto& itJ2Pos : rowInfo.indexedPositions) { - size_t tapeJ = itJ2Pos.first; - const std::vector& positions = itJ2Pos.second; - - CGBase jacVal = dyiDxtape[tapeI].at(tapeJ) * py; - - indexedLoopResults[jacLE++] = createJacobianElement(handler, positions, - jacVal, iterationIndexOp, ifElses, - allLocations); - } - - /** - * non-indexed variable contributions - */ - // original J index -> {locationIt0, locationIt1, ...} - for (const auto& itJ2Pos : rowInfo.nonIndexedPositions) { - size_t j = itJ2Pos.first; - const std::vector& positions = itJ2Pos.second; - - CGBase jacVal = Base(0); - - // non-indexed variables used directly - const LoopPosition* pos = lModel.getNonIndexedIndepIndexes(j); - if (pos != nullptr) { - size_t tapeJ = pos->tape; - const auto itVal = dyiDxtape[tapeI].find(tapeJ); - if (itVal != dyiDxtape[tapeI].end()) { - jacVal += itVal->second; - } - } - - // non-indexed variables used through temporary variables - const auto itks = rowInfo.tmpEvals.find(j); - if (itks != rowInfo.tmpEvals.end()) { - const std::set& ks = itks->second; - for (size_t k : ks) { - size_t tapeJ = lModel.getTempIndepIndexes(k)->tape; - - jacVal += dyiDxtape[tapeI].at(tapeJ) * dzDx[k].at(j); - } - } - - jacVal *= py; - - indexedLoopResults[jacLE++] = createJacobianElement(handler, positions, - jacVal, iterationIndexOp, ifElses, - allLocations); - } -} - - -namespace loops { - -template -std::pair, IndexPattern*> createJacobianElement(CodeHandler& handler, - const std::vector& positions, - const CG& dfdx, - IndexOperationNode& iterationIndexOp, - std::vector >& ifElses, - std::set& allLocations) { - using namespace std; - - size_t nIter = positions.size(); - - map locations; - for (size_t iter = 0; iter < nIter; iter++) { - if (positions[iter] != std::numeric_limits::max()) { - locations[iter] = positions[iter]; - allLocations.insert(positions[iter]); - } - } - - IndexPattern* pattern; - if (locations.size() == nIter) { - // present in all iterations - - // generate the index pattern for the Jacobian compressed element - pattern = IndexPattern::detect(positions); - handler.manageLoopDependentIndexPattern(pattern); - } else { - /** - * must create a conditional element so that this - * contribution to the Jacobian is only evaluated at the - * relevant iterations - */ - - // generate the index pattern for the Jacobian compressed element - pattern = IndexPattern::detect(locations); - handler.manageLoopDependentIndexPattern(pattern); - } - - - return createLoopResult(handler, locations, nIter, - dfdx, pattern, 1, - iterationIndexOp, ifElses); - -} - -} // END loops namespace - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_jac_fr1.hpp b/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_jac_fr1.hpp deleted file mode 100644 index 9f70bce82..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_jac_fr1.hpp +++ /dev/null @@ -1,72 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_JAC_FR1_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_JAC_FR1_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -void ModelCSourceGen::generateSparseJacobianWithLoopsSourceFromForRev(const std::map& jacInfo, - size_t maxCompressedSize, - const std::string& localFunctionTypeName, - const std::string& suffix, - const std::string& keyName, - const std::map >& nonLoopElements, - const std::map*, std::map > > >& loopGroups, - void (*generateLocalFunctionName)(std::ostringstream& cache, const std::string& modelName, const LoopModel& loop, size_t g)) { - using namespace std; - using namespace CppAD::cg::loops; - - startingJob("'sparse Jacobian'", JobTimer::SOURCE_GENERATION); - - /** - * Generate the source code - */ - LanguageC langC(_baseTypeName); - string argsDcl = langC.generateDefaultFunctionArgumentsDcl(); - - string model_function = _name + "_" + FUNCTION_SPARSE_JACOBIAN; - string localFunction = _name + "_" + localFunctionTypeName; - string nlSuffix = "noloop_" + suffix; - - _cache.str(""); - _cache << "#include \n" - << LanguageC::ATOMICFUN_STRUCT_DEFINITION << "\n\n"; - - generateFunctionDeclarationSource(_cache, localFunction, nlSuffix, nonLoopElements, argsDcl); - generateFunctionDeclarationSourceLoopForRev(_cache, langC, _name, keyName, loopGroups, generateLocalFunctionName); - - _cache << "\n"; - printForRevUsageFunction(_cache, _baseTypeName, _name, - model_function, 2, - localFunction, suffix, - keyName, "it", "jac", - loopGroups, - nonLoopElements, - jacInfo, - generateLocalFunctionName, - _jacSparsity.rows.size(), maxCompressedSize); - - finishedJob(); - - _sources[model_function + ".c"] = _cache.str(); - _cache.str(""); -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_rev1.hpp b/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_rev1.hpp deleted file mode 100644 index 2d4aadb75..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_rev1.hpp +++ /dev/null @@ -1,461 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_REV1_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_REV1_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/*************************************************************************** - * Methods related with loop insertion into the operation graph - **************************************************************************/ - -/** - * - * @param sources maps files names to the generated source code - * @param elements [equation]{vars} - */ -template -void ModelCSourceGen::prepareSparseReverseOneWithLoops(const std::map >& elements) { - using namespace std; - using namespace CppAD::cg::loops; - - //printSparsityPattern(_jacSparsity.rows, _jacSparsity.cols, "jacobian", _fun.Range()); - - size_t n = _fun.Domain(); - - CodeHandler handler; - handler.setJobTimer(_jobTimer); - handler.setZeroDependents(false); - - auto& indexJrowDcl = *handler.makeIndexDclrNode("jrow"); - auto& indexIterationDcl = *handler.makeIndexDclrNode(LoopModel::ITERATION_INDEX_NAME); - auto& iterationIndexOp = *handler.makeIndexNode(indexIterationDcl); - auto& jrowIndexOp = *handler.makeIndexNode(indexJrowDcl); - - std::vector*> localNodes(4); - localNodes[0] = &indexJrowDcl; - localNodes[1] = &indexIterationDcl; - localNodes[2] = &iterationIndexOp; - localNodes[3] = &jrowIndexOp; - - size_t nonIndexdedEqSize = _funNoLoops != nullptr ? _funNoLoops->getOrigDependentIndexes().size() : 0; - - std::vector > noLoopEvalSparsity; - std::vector > > noLoopEvalLocations; // tape equation -> original J -> locations - map*, std::vector > > loopsEvalSparsities; - map*, std::vector > loopEqInfo; - - size_t nnz = _jacSparsity.rows.size(); - std::vector rows(nnz); - std::vector cols(nnz); - std::vector locations(nnz); - - size_t p = 0; - for (const auto& itI : elements) {//loop dependents/equations - size_t i = itI.first; - const std::vector& r = itI.second; - - for (size_t e = 0; e < r.size(); e++) { // loop variables - rows[p] = i; - cols[p] = r[e]; - locations[p] = e; - p++; - } - } - CPPADCG_ASSERT_UNKNOWN(p == nnz); - - analyseSparseJacobianWithLoops(rows, cols, locations, - noLoopEvalSparsity, noLoopEvalLocations, loopsEvalSparsities, loopEqInfo); - - std::vector x(n); - handler.makeVariables(x); - if (_x.size() > 0) { - for (size_t i = 0; i < n; i++) { - x[i].setValue(_x[i]); - } - } - - CGBase py; - handler.makeVariable(py); - if (_x.size() > 0) { - py.setValue(Base(1.0)); - } - - /*********************************************************************** - * generate the operation graph - **********************************************************************/ - - /** - * original equations outside the loops - */ - // temporaries (zero orders) - std::vector tmps; - - // jacobian for temporaries - std::vector > dzDx(_funNoLoops != nullptr ? _funNoLoops->getTemporaryDependentCount() : 0); - - /******************************************************************* - * equations NOT in loops - ******************************************************************/ - if (_funNoLoops != nullptr) { - ADFun& fun = _funNoLoops->getTape(); - - /** - * zero order - */ - std::vector depNL = _funNoLoops->getTape().Forward(0, x); - - tmps.resize(depNL.size() - nonIndexdedEqSize); - for (size_t i = 0; i < tmps.size(); i++) - tmps[i] = depNL[nonIndexdedEqSize + i]; - - /** - * jacobian - */ - bool hasAtomics = isAtomicsUsed(); // TODO: improve this by checking only the current fun - std::vector > dydx = generateLoopRev1Jac(fun, _funNoLoops->getJacobianSparsity(), noLoopEvalSparsity, x, hasAtomics); - - const std::vector& dependentIndexes = _funNoLoops->getOrigDependentIndexes(); - map > jacNl; // by row - - for (size_t inl = 0; inl < nonIndexdedEqSize; inl++) { - size_t i = dependentIndexes[inl]; - - // prepare space for the jacobian of the original equations - std::vector& row = jacNl[i]; - row.resize(dydx[inl].size()); - - for (const auto& itjv : dydx[inl]) { - size_t j = itjv.first; - // (dy_i/dx_v) elements from equations outside loops - const set& locations = noLoopEvalLocations[inl][j]; - - CPPADCG_ASSERT_UNKNOWN(locations.size() == 1); // one jacobian element should not be placed in several locations - size_t e = *locations.begin(); - - row[e] = itjv.second * py; - - _nonLoopRev1Elements[i].insert(e); - } - } - - // dz_k/dx_v (for temporary variable) - for (size_t inl = nonIndexdedEqSize; inl < dydx.size(); inl++) { - size_t k = inl - nonIndexdedEqSize; - - for (const auto& itjv : dydx[inl]) { - size_t j = itjv.first; - dzDx[k][j] = itjv.second; - } - } - - /** - * Create source for each variable present in equations outside loops - */ - typename map >::iterator itJ; - for (itJ = jacNl.begin(); itJ != jacNl.end(); ++itJ) { - createReverseOneWithLoopsNL(handler, itJ->first, itJ->second); - } - } - - /*********************************************************************** - * equations in loops - **********************************************************************/ - typename map*, std::vector >::iterator itl2Eq; - for (itl2Eq = loopEqInfo.begin(); itl2Eq != loopEqInfo.end(); ++itl2Eq) { - LoopModel& lModel = *itl2Eq->first; - const std::vector& info = itl2Eq->second; - ADFun& fun = lModel.getTape(); - const std::vector >& dependentIndexes = lModel.getDependentIndexes(); - size_t nIterations = lModel.getIterationCount(); - - _cache.str(""); - _cache << "model (reverse one, loop " << lModel.getLoopId() << ")"; - std::string jobName = _cache.str(); - - /** - * evaluate loop model Jacobian - */ - startingJob("'" + jobName + "'", JobTimer::GRAPH); - - std::vector indexedIndeps = createIndexedIndependents(handler, lModel, iterationIndexOp); - std::vector xl = createLoopIndependentVector(handler, lModel, indexedIndeps, x, tmps); - - bool hasAtomics = isAtomicsUsed(); // TODO: improve this by checking only the current fun - std::vector > dyiDxtape = generateLoopRev1Jac(fun, lModel.getJacobianSparsity(), loopsEvalSparsities[&lModel], xl, hasAtomics); - - finishedJob(); - - /** - * process each equation pattern (row in the loop tape) - */ - std::vector > indexedLoopResults; - for (size_t tapeI = 0; tapeI < info.size(); tapeI++) { - const JacobianWithLoopsRowInfo& rowInfo = info[tapeI]; - - size_t maxRowEls = rowInfo.indexedPositions.size() + rowInfo.nonIndexedPositions.size(); - if (maxRowEls == 0) - continue; // nothing to do (possibly an equation assigned to a constant value) - - /** - * determine iteration index through the row index - */ - map irow2It; - for (size_t it = 0; it < nIterations; it++) { - size_t i = dependentIndexes[tapeI][it].original; - if (i < _fun.Range()) // some equations are not present in all iteration - irow2It[i] = it; - } - - std::unique_ptr itPattern(IndexPattern::detect(irow2It)); - auto* iterationIndexPatternOp = handler.makeIndexAssignNode(indexIterationDcl, *itPattern.get(), jrowIndexOp); - iterationIndexOp.makeAssigmentDependent(*iterationIndexPatternOp); - - /** - * generate the operation graph for this equation pattern - */ - std::set allLocations; - indexedLoopResults.resize(maxRowEls); - size_t jacLE = 0; - - std::vector > ifElses; - - prepareSparseJacobianRowWithLoops(handler, lModel, - tapeI, rowInfo, - dyiDxtape, dzDx, - py, - iterationIndexOp, ifElses, - jacLE, indexedLoopResults, allLocations); - indexedLoopResults.resize(jacLE); - - std::vector pxCustom(indexedLoopResults.size()); - - for (size_t i = 0; i < indexedLoopResults.size(); i++) { - const CGBase& val = indexedLoopResults[i].first; - IndexPattern* ip = indexedLoopResults[i].second; - - pxCustom[i] = createLoopDependentFunctionResult(handler, i, val, ip, iterationIndexOp); - } - - /** - * save information on: row->{compressed reverse 1 position} - */ - std::map >& row2position = _loopRev1Groups[&lModel][tapeI]; - - for (size_t it = 0; it < nIterations; it++) { - size_t i = dependentIndexes[tapeI][it].original; - if (i < _fun.Range()) { // some equations are not present in all iteration - std::set positions; - - for (const auto& itc : rowInfo.indexedPositions) { - const std::vector& positionsC = itc.second; - if (positionsC[it] != std::numeric_limits::max()) // not all elements are requested for all iterations - positions.insert(positionsC[it]); - } - for (const auto& itc : rowInfo.nonIndexedPositions) { - const std::vector& positionsC = itc.second; - if (positionsC[it] != std::numeric_limits::max()) // not all elements are requested for all iterations - positions.insert(positionsC[it]); - } - - if (!positions.empty()) - row2position[i].swap(positions); - } - } - - /** - * Generate the source code - */ - LanguageC langC(_baseTypeName); - langC.setFunctionIndexArgument(indexJrowDcl); - langC.setParameterPrecision(_parameterPrecision); - - _cache.str(""); - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("dw")); - LangCDefaultHessianVarNameGenerator nameGenHess(nameGen.get(), "dy", n); - - /** - * Generate the source code inside the loop - */ - _cache.str(""); - _cache << "model (reverse one, loop " << lModel.getLoopId() << ", group " << tapeI << ")"; - string jobName = _cache.str(); - handler.generateCode(code, langC, pxCustom, nameGenHess, _atomicFunctions, jobName); - - _cache.str(""); - generateFunctionNameLoopRev1(_cache, lModel, tapeI); - std::string functionName = _cache.str(); - - std::string argsDcl = langC.generateFunctionArgumentsDcl(); - - _cache.str(""); - _cache << "#include \n" - "#include \n" - "\n" - << LanguageC::ATOMICFUN_STRUCT_DEFINITION << "\n" - "\n" - "void " << functionName << "(" << argsDcl << ") {\n"; - nameGenHess.customFunctionVariableDeclarations(_cache); - _cache << langC.generateIndependentVariableDeclaration() << "\n"; - _cache << langC.generateDependentVariableDeclaration() << "\n"; - _cache << langC.generateTemporaryVariableDeclaration(false, false, - handler.getExternalFuncMaxForwardOrder(), - handler.getExternalFuncMaxReverseOrder()) << "\n"; - nameGenHess.prepareCustomFunctionVariables(_cache); - - // code inside the loop - _cache << code.str(); - - nameGenHess.finalizeCustomFunctionVariables(_cache); - _cache << "}\n\n"; - - _sources[functionName + ".c"] = _cache.str(); - _cache.str(""); - - /** - * prepare the nodes to be reused! - */ - if (tapeI + 1 < info.size() || &lModel != loopEqInfo.rbegin()->first) { - handler.resetNodes(); // uncolor nodes - } - } - - } - - /** - * - */ - string functionRev1 = _name + "_" + FUNCTION_SPARSE_REVERSE_ONE; - _sources[functionRev1 + ".c"] = generateGlobalForRevWithLoopsFunctionSource(elements, - _loopRev1Groups, _nonLoopRev1Elements, - functionRev1, _name, _baseTypeName, "dep", - generateFunctionNameLoopRev1); - /** - * Sparsity - */ - _cache.str(""); - generateSparsity1DSource2(_name + "_" + FUNCTION_REVERSE_ONE_SPARSITY, elements); - _sources[_name + "_" + FUNCTION_REVERSE_ONE_SPARSITY + ".c"] = _cache.str(); - _cache.str(""); -} - -template -void ModelCSourceGen::createReverseOneWithLoopsNL(CodeHandler& handler, - size_t i, - std::vector >& jacRow) { - size_t n = _fun.Domain(); - - _cache.str(""); - _cache << "model (forward one, dep " << i << ") no loop"; - const std::string jobName = _cache.str(); - - LanguageC langC(_baseTypeName); - langC.setMaxAssigmentsPerFunction(_maxAssignPerFunc, &_sources); - langC.setParameterPrecision(_parameterPrecision); - _cache.str(""); - _cache << _name << "_" << FUNCTION_SPARSE_REVERSE_ONE << "_noloop_dep" << i; - langC.setGenerateFunction(_cache.str()); - - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("dw")); - LangCDefaultHessianVarNameGenerator nameGenHess(nameGen.get(), "dy", n); - - handler.generateCode(code, langC, jacRow, nameGenHess, _atomicFunctions, jobName); - - handler.resetNodes(); -} - -template -std::vector > > ModelCSourceGen::generateLoopRev1Jac(ADFun& fun, - const SparsitySetType& sparsity, - const SparsitySetType& evalSparsity, - const std::vector& x, - bool constainsAtomics) { - using namespace std; - - size_t m = fun.Range(); - - std::vector > dyDx(m); - - if (!constainsAtomics) { - std::vector row, col; - generateSparsityIndexes(evalSparsity, row, col); - - if (row.size() == 0) - return dyDx; // nothing to do - - std::vector jacLoop(row.size()); - - CppAD::sparse_jacobian_work work; // temporary structure for CppAD - fun.SparseJacobianReverse(x, sparsity, row, col, jacLoop, work); - - // organize results - for (size_t el = 0; el < jacLoop.size(); el++) { - size_t i = row[el]; - size_t j = col[el]; - dyDx[i][j] = jacLoop[el]; - } - - } else { - - std::vector w(m); - - for (size_t i = 0; i < m; i++) { - const set& row = evalSparsity[i]; - - if (row.empty()) - continue; - - fun.Forward(0, x); - - w[i] = Base(1); - std::vector dw = fun.Reverse(1, w); - CPPADCG_ASSERT_UNKNOWN(dw.size() == fun.Domain()); - w[i] = Base(0); - - map& dyIDx = dyDx[i]; - - for (size_t j : row) { - dyIDx[j] = dw[j]; - } - } - - } - - return dyDx; -} - -template -void ModelCSourceGen::generateFunctionNameLoopRev1(std::ostringstream& cache, - const LoopModel& loop, - size_t tapeI) { - generateFunctionNameLoopRev1(cache, _name, loop, tapeI); -} - -template -void ModelCSourceGen::generateFunctionNameLoopRev1(std::ostringstream& cache, - const std::string& modelName, - const LoopModel& loop, - size_t tapeI) { - cache << modelName << "_" << FUNCTION_SPARSE_REVERSE_ONE << - "_loop" << loop.getLoopId() << "_g" << tapeI; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_rev2.hpp b/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_rev2.hpp deleted file mode 100644 index d14b3c5d5..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/patterns/model_c_source_gen_loops_rev2.hpp +++ /dev/null @@ -1,1326 +0,0 @@ -#ifndef CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_REV2_INCLUDED -#define CPPAD_CG_MODEL_C_SOURCE_GEN_LOOPS_REV2_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/*************************************************************************** - * Utility classes and functions - **************************************************************************/ -namespace loops { - -template -class HessianWithLoopsInfo; - -template -class HessianTermContrib; - -template -bool operator<(const HessianTermContrib& l, const HessianTermContrib& r); - -template -class HessianRowGroup; - -template -std::vector, IndexPattern*> > generateReverseTwoGroupOps(CodeHandler& handler, - const LoopModel& lModel, - const loops::HessianWithLoopsInfo& info, - HessianRowGroup& group, - const CG& tx1, - const std::map > >& dzDx, - std::map >& jrow2CompressedLoc); - -template -std::pair, IndexPattern*> createReverseMode2Contribution(CodeHandler& handler, - HessianRowGroup& group, - const std::vector& positions, - const CG& ddfdxdx, - const CG& tx1, - IndexOperationNode& iterationIndexOp, - std::map >& jrow2CompressedLoc); -} // END loops namespace - -/*************************************************************************** - * Methods related with loop insertion into the operation graph - **************************************************************************/ - -template -void ModelCSourceGen::prepareSparseReverseTwoWithLoops(const std::map >& elements) { - using namespace std; - using namespace CppAD::cg::loops; - - size_t m = _fun.Range(); - size_t n = _fun.Domain(); - - CodeHandler handler; - handler.setJobTimer(_jobTimer); - handler.setZeroDependents(false); - - auto& indexJrowDcl = *handler.makeIndexDclrNode("jrow"); - auto& indexLocalItDcl = *handler.makeIndexDclrNode("it"); - auto& indexLocalItCountDcl = *handler.makeIndexDclrNode("itCount"); - auto& indexIterationDcl = *handler.makeIndexDclrNode(LoopModel::ITERATION_INDEX_NAME); - auto& jrowIndexOp = *handler.makeIndexNode(indexJrowDcl); - - std::vector* > localNodes(5); - localNodes[0] = &indexJrowDcl; - localNodes[1] = &indexLocalItDcl; - localNodes[2] = &indexLocalItCountDcl; - localNodes[3] = &indexIterationDcl; - localNodes[4] = &jrowIndexOp; - - // independent variables - std::vector x(n); - handler.makeVariables(x); - if (_x.size() > 0) { - for (size_t i = 0; i < n; i++) { - x[i].setValue(_x[i]); - } - } - - CGBase tx1; - handler.makeVariable(tx1); - if (_x.size() > 0) { - tx1.setValue(Base(1.0)); - } - - // multipliers - std::vector py(m); // (k+1)*m is not used because we are not interested in all values - handler.makeVariables(py); - if (_x.size() > 0) { - for (size_t i = 0; i < m; i++) { - py[i].setValue(Base(1.0)); - } - } - - size_t nonIndexdedEqSize = _funNoLoops != nullptr ? _funNoLoops->getOrigDependentIndexes().size() : 0; - - size_t nnz = 0; - for (const auto& itJrow2jcols : elements) { - nnz += itJrow2jcols.second.size(); - } - - std::vector hessRows(nnz); - std::vector hessCols(nnz); - std::vector hessOrder(nnz); - size_t ge = 0; - for (const auto& itJrow2jcols : elements) { - size_t jrow = itJrow2jcols.first; - const std::vector& jcols = itJrow2jcols.second; - - for (size_t e = 0; e < jcols.size(); e++) { - hessRows[ge] = jrow; - hessCols[ge] = jcols[e]; - hessOrder[ge] = e; - ge++; - } - } - - std::vector > noLoopEvalJacSparsity; - std::vector > noLoopEvalHessSparsity; - std::vector > > noLoopEvalHessLocations; - map*, loops::HessianWithLoopsInfo > loopHessInfo; - - analyseSparseHessianWithLoops(hessRows, hessCols, hessOrder, - noLoopEvalJacSparsity, noLoopEvalHessSparsity, - noLoopEvalHessLocations, loopHessInfo, false); - - /*********************************************************************** - * generate the operation graph - **********************************************************************/ - /** - * Calculate Hessians and Jacobians - */ - // temporaries (zero orders) - std::vector tmpsAlias; - if (_funNoLoops != nullptr) { - ADFun& fun = _funNoLoops->getTape(); - - tmpsAlias.resize(fun.Range() - nonIndexdedEqSize); - for (size_t k = 0; k < tmpsAlias.size(); k++) { - // to be defined later - tmpsAlias[k] = CG(*handler.makeNode(CGOpCode::Alias)); - } - } - - /** - * prepare loop independents - */ - typename map*, HessianWithLoopsInfo >::iterator itLoop2Info; - for (itLoop2Info = loopHessInfo.begin(); itLoop2Info != loopHessInfo.end(); ++itLoop2Info) { - LoopModel& lModel = *itLoop2Info->first; - HessianWithLoopsInfo& info = itLoop2Info->second; - - info.iterationIndexOp = handler.makeIndexNode(indexIterationDcl); - set*> indexesOps; - indexesOps.insert(info.iterationIndexOp); - - /** - * make the loop's indexed variables - */ - std::vector indexedIndeps = createIndexedIndependents(handler, lModel, *info.iterationIndexOp); - info.x = createLoopIndependentVector(handler, lModel, indexedIndeps, x, tmpsAlias); - - info.w = createLoopDependentVector(handler, lModel, *info.iterationIndexOp); - } - - /** - * Calculate Hessians and Jacobians - */ - /** - * Loops - evaluate Jacobian and Hessian - */ - bool hasAtomics = isAtomicsUsed(); // TODO: improve this by checking only the current fun - //const std::map >& aaa = getAtomicsIndeps(); - - for (itLoop2Info = loopHessInfo.begin(); itLoop2Info != loopHessInfo.end(); ++itLoop2Info) { - LoopModel& lModel = *itLoop2Info->first; - HessianWithLoopsInfo& info = itLoop2Info->second; - - _cache.str(""); - _cache << "model (Jacobian + Hessian, loop " << lModel.getLoopId() << ")"; - std::string jobName = _cache.str(); - - startingJob("'" + jobName + "'", JobTimer::GRAPH); - - info.evalLoopModelJacobianHessian(hasAtomics); - - finishedJob(); - } - - /** - * No loops - */ - map > dzDx; - if (_funNoLoops != nullptr) { - ADFun& fun = _funNoLoops->getTape(); - std::vector yNL(fun.Range()); - - /** - * Jacobian and Hessian - temporary variables - */ - startingJob("'model (Jacobian + Hessian, temporaries)'", JobTimer::GRAPH); - - dzDx = _funNoLoops->calculateJacobianHessianUsedByLoops(handler, - loopHessInfo, x, yNL, - noLoopEvalJacSparsity, - hasAtomics); - - finishedJob(); - - for (size_t i = 0; i < tmpsAlias.size(); i++) - tmpsAlias[i].getOperationNode()->getArguments().push_back(asArgument(yNL[nonIndexdedEqSize + i])); - - for (itLoop2Info = loopHessInfo.begin(); itLoop2Info != loopHessInfo.end(); ++itLoop2Info) { - HessianWithLoopsInfo& info = itLoop2Info->second; - // not needed anymore: - info.dyiDzk.clear(); - } - } - - /** - * Loops - Hessian - */ - for (itLoop2Info = loopHessInfo.begin(); itLoop2Info != loopHessInfo.end(); ++itLoop2Info) { - LoopModel& lModel = *itLoop2Info->first; - HessianWithLoopsInfo& info = itLoop2Info->second; - - /******************************************************************* - * create Hessian row groups - * for the contributions from the equations in loops - ******************************************************************/ - SmartVectorPointer > loopGroups; - - generateHessianRowGroups(lModel, info, n, loopGroups); - - /******************************************************************* - * generate the operation graph for each Hessian row subgroup - ******************************************************************/ - for (size_t g = 0; g < loopGroups.size(); g++) { - HessianRowGroup& group = *loopGroups[g]; - - /** - * determine if a loop should be created - */ - LoopStartOperationNode* loopStart = nullptr; - - map > localIterCount2Jrows; - - for (const auto& itJrow2It : group.jRow2Iterations) { - size_t jrow = itJrow2It.first; - size_t itCount = itJrow2It.second.size(); - localIterCount2Jrows[itCount].insert(jrow); - } - - bool createsLoop = localIterCount2Jrows.size() != 1 || // is there a different number of it - localIterCount2Jrows.begin()->first != 1; // is there always just on iteration? - - /** - * Model index pattern - * - * detect the index pattern for the model iterations - * based on jrow and the local loop iteration - */ - map > jrow2localIt2ModelIt; - - for (const auto& itJrow2It : group.jRow2Iterations) { - size_t jrow = itJrow2It.first; - - map& localIt2ModelIt = jrow2localIt2ModelIt[jrow]; - size_t localIt = 0; - for (auto itIt = itJrow2It.second.begin(); itIt != itJrow2It.second.end(); ++itIt, localIt++) { - localIt2ModelIt[localIt] = *itIt; - } - } - - /** - * try to fit a combination of two patterns: - * j = fStart(jrow) + flit(lit); - */ - std::unique_ptr itPattern(Plane2DIndexPattern::detectPlane2D(jrow2localIt2ModelIt)); - - if (itPattern.get() == nullptr) { - // did not match! - itPattern.reset(new Random2DIndexPattern(jrow2localIt2ModelIt)); - } - - /** - * Local iteration count pattern - */ - IndexOperationNode* localIterIndexOp = nullptr; - IndexOperationNode* localIterCountIndexOp = nullptr; - IndexAssignOperationNode* itCountAssignOp = nullptr; - std::unique_ptr indexLocalItCountPattern; - - if (createsLoop) { - map jrow2litCount; - - for (const auto& itJrow2Its : group.jRow2Iterations) { - size_t jrow = itJrow2Its.first; - jrow2litCount[jrow] = itJrow2Its.second.size(); - } - - indexLocalItCountPattern.reset(IndexPattern::detect(jrow2litCount)); - - if (IndexPattern::isConstant(*indexLocalItCountPattern.get())) { - size_t itCount = group.jRow2Iterations.begin()->second.size(); - loopStart = handler.makeLoopStartNode(indexLocalItDcl, itCount); - } else { - itCountAssignOp = handler.makeIndexAssignNode(indexLocalItCountDcl, *indexLocalItCountPattern.get(), jrowIndexOp); - localIterCountIndexOp = handler.makeIndexNode(*itCountAssignOp); - loopStart = handler.makeLoopStartNode(indexLocalItDcl, *localIterCountIndexOp); - } - - localIterIndexOp = handler.makeIndexNode(*loopStart); - } - - - auto* iterationIndexPatternOp = handler.makeIndexAssignNode(indexIterationDcl, *itPattern.get(), &jrowIndexOp, localIterIndexOp); - info.iterationIndexOp->makeAssigmentDependent(*iterationIndexPatternOp); - - map > jrow2CompressedLoc; - std::vector, IndexPattern*> > indexedLoopResults; - - indexedLoopResults = generateReverseTwoGroupOps(handler, lModel, info, - group, tx1, - dzDx, - jrow2CompressedLoc); - - _loopRev2Groups[&lModel][g] = jrow2CompressedLoc; - - LoopEndOperationNode* loopEnd = nullptr; - std::vector pxCustom; - if (createsLoop) { - /** - * make the loop end - */ - size_t assignOrAdd = 1; - set*> indexesOps; - indexesOps.insert(info.iterationIndexOp); - loopEnd = createLoopEnd(handler, *loopStart, indexedLoopResults, indexesOps, assignOrAdd); - - /** - * move non-indexed expressions outside loop - */ - moveNonIndexedOutsideLoop(handler, *loopStart, *loopEnd); - - /** - * - */ - pxCustom.resize(1); - - // {0} : must point to itself since there is only one dependent - pxCustom[0] = handler.createCG(*handler.makeNode(CGOpCode::DependentRefRhs,{0},{*loopEnd})); - - } else { - /** - * No loop required - */ - pxCustom.resize(indexedLoopResults.size()); - for (size_t i = 0; i < indexedLoopResults.size(); i++) { - const CGBase& val = indexedLoopResults[i].first; - IndexPattern* ip = indexedLoopResults[i].second; - - pxCustom[i] = createLoopDependentFunctionResult(handler, i, val, ip, *info.iterationIndexOp); - } - - } - - LanguageC langC(_baseTypeName); - langC.setFunctionIndexArgument(indexJrowDcl); - langC.setParameterPrecision(_parameterPrecision); - - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("px")); - LangCDefaultReverse2VarNameGenerator nameGenRev2(nameGen.get(), n, 1); - - /** - * Generate the source code inside the loop - */ - _cache.str(""); - _cache << "model (reverse two, loop " << lModel.getLoopId() << ", group " << g << ")"; - string jobName = _cache.str(); - handler.generateCode(code, langC, pxCustom, nameGenRev2, _atomicFunctions, jobName); - - _cache.str(""); - generateFunctionNameLoopRev2(_cache, lModel, g); - std::string functionName = _cache.str(); - - std::string argsDcl = langC.generateFunctionArgumentsDcl(); - - _cache.str(""); - _cache << "#include \n" - "#include \n" - "\n" - << LanguageC::ATOMICFUN_STRUCT_DEFINITION << "\n" - "\n" - "void " << functionName << "(" << argsDcl << ") {\n"; - nameGenRev2.customFunctionVariableDeclarations(_cache); - _cache << langC.generateIndependentVariableDeclaration() << "\n"; - _cache << langC.generateDependentVariableDeclaration() << "\n"; - _cache << langC.generateTemporaryVariableDeclaration(false, false, - handler.getExternalFuncMaxForwardOrder(), - handler.getExternalFuncMaxReverseOrder()) << "\n"; - nameGenRev2.prepareCustomFunctionVariables(_cache); - - // code inside the loop - _cache << code.str(); - - nameGenRev2.finalizeCustomFunctionVariables(_cache); - _cache << "}\n\n"; - - _sources[functionName + ".c"] = _cache.str(); - _cache.str(""); - - /** - * prepare the nodes to be reused! - */ - if (g + 1 < loopGroups.size()) { - handler.resetNodes(); // uncolor nodes - } - } - - } - - /******************************************************************* - * equations NOT in loops - ******************************************************************/ - if (_funNoLoops != nullptr) { - ADFun& fun = _funNoLoops->getTape(); - - /** - * hessian - original equations - */ - std::vector row, col; - generateSparsityIndexes(noLoopEvalHessSparsity, row, col); - - if (row.size() > 0) { - const string jobName = "model (reverse two, no loops)"; - startingJob("'" + jobName + "'", JobTimer::SOURCE_GENERATION); - - // we can use a new handler to reduce memory usage - CodeHandler handlerNL; - handlerNL.setJobTimer(_jobTimer); - - std::vector tx0(n); - handlerNL.makeVariables(tx0); - if (_x.size() > 0) { - for (size_t i = 0; i < n; i++) { - tx0[i].setValue(_x[i]); - } - } - - CGBase tx1; - handlerNL.makeVariable(tx1); - if (_x.size() > 0) { - tx1.setValue(Base(1.0)); - } - - std::vector py(m); // (k+1)*m is not used because we are not interested in all values - handlerNL.makeVariables(py); - - std::vector pyNoLoop(_funNoLoops->getTapeDependentCount()); - - const std::vector& origIndexes = _funNoLoops->getOrigDependentIndexes(); - for (size_t inl = 0; inl < origIndexes.size(); inl++) { - pyNoLoop[inl] = py[origIndexes[inl]]; - if (_x.size() > 0) { - pyNoLoop[inl].setValue(Base(1.0)); - } - } - - std::vector hessNoLoop(row.size()); - - CppAD::sparse_hessian_work work; // temporary structure for CPPAD - // "cppad.symmetric" may have missing values for functions using - // atomic functions which only provide half of the elements - // (some values could be zeroed) - work.color_method = "cppad.general"; - fun.SparseHessian(tx0, pyNoLoop, _funNoLoops->getHessianOrigEqsSparsity(), row, col, hessNoLoop, work); - - map > hess; - // save non-indexed hessian elements - for (size_t el = 0; el < row.size(); el++) { - size_t j1 = row[el]; - size_t j2 = col[el]; - const set& locations = noLoopEvalHessLocations[j1][j2]; - for (size_t itE : locations) { - hess[j1][itE] = hessNoLoop[el]; - _nonLoopRev2Elements[j1].insert(itE); - } - } - - /** - * Generate one function for each independent variable / hessian row - */ - for (const auto& it : hess) { - size_t j = it.first; - const map& cols = it.second; - - _cache.str(""); - _cache << "model (reverse two, no loops, indep " << j << ")"; - const string subJobName = _cache.str(); - - std::vector pxCustom(elements.at(j).size()); - - for (const auto& it2 : cols) { - size_t e = it2.first; - pxCustom[e] = it2.second * tx1; - } - - LanguageC langC(_baseTypeName); - langC.setMaxAssigmentsPerFunction(_maxAssignPerFunc, &_sources); - langC.setParameterPrecision(_parameterPrecision); - _cache.str(""); - _cache << _name << "_" << FUNCTION_SPARSE_REVERSE_TWO << "_noloop_indep" << j; - string functionName = _cache.str(); - langC.setGenerateFunction(functionName); - - std::ostringstream code; - std::unique_ptr > nameGen(createVariableNameGenerator("px")); - LangCDefaultReverse2VarNameGenerator nameGenRev2(nameGen.get(), n, 1); - - handlerNL.generateCode(code, langC, pxCustom, nameGenRev2, _atomicFunctions, subJobName); - } - - finishedJob(); - } - - } - - /** - * - */ - string functionRev2 = _name + "_" + FUNCTION_SPARSE_REVERSE_TWO; - _sources[functionRev2 + ".c"] = generateGlobalForRevWithLoopsFunctionSource(elements, - _loopRev2Groups, _nonLoopRev2Elements, - functionRev2, _name, _baseTypeName, "indep", - generateFunctionNameLoopRev2); - /** - * Sparsity - */ - _cache.str(""); - generateSparsity1DSource2(_name + "_" + FUNCTION_REVERSE_TWO_SPARSITY, elements); - _sources[_name + "_" + FUNCTION_REVERSE_TWO_SPARSITY + ".c"] = _cache.str(); - _cache.str(""); -} - -namespace loops { - -template -void generateHessianRowGroups(const LoopModel& lModel, - const HessianWithLoopsInfo& info, - size_t n, - SmartVectorPointer >& loopGroups) { - using namespace std; - using namespace CppAD::cg::loops; - - /** - * group rows with the same contribution terms - */ - map > > indexedIndexed2jrow2Iter; - map > > indexedNonIndexed2jrow2Iter; - map > > indexedTemp2jrow2Iter; - map > > nonIndexedIndexed2jrow2Iter; - map > > tempIndexed2jrow2Iter; - - map, set > contrib2jrows = groupHessianRowsByContrib(info, n, - indexedIndexed2jrow2Iter, - indexedNonIndexed2jrow2Iter, - indexedTemp2jrow2Iter, - nonIndexedIndexed2jrow2Iter, - tempIndexed2jrow2Iter); - - loopGroups.reserve(contrib2jrows.size() *2); // TODO: improve this - - for (const auto& itC : contrib2jrows) { - const HessianTermContrib& c = itC.first; - const set& jrows = itC.second; - - /** - * create subgroups - */ - subgroupHessianRowsByContrib(info, c, jrows, - indexedIndexed2jrow2Iter, - indexedNonIndexed2jrow2Iter, - indexedTemp2jrow2Iter, - nonIndexedIndexed2jrow2Iter, - tempIndexed2jrow2Iter, - loopGroups); - } - -} - -template -std::vector, IndexPattern*> > generateReverseTwoGroupOps(CodeHandler& handler, - const LoopModel& lModel, - const HessianWithLoopsInfo& info, - HessianRowGroup& group, - const CG& tx1, - const std::map > >& dzDx, - std::map >& jrow2CompressedLoc) { - using namespace std; - using namespace CppAD::cg::loops; - - typedef CG CGBase; - - IndexOperationNode& iterationIndexOp = *info.iterationIndexOp; - - // store results in indexedLoopResults - size_t hessElSize = group.size(); - - std::vector > indexedLoopResults(hessElSize); - size_t hessLE = 0; - - map >::const_iterator itPos; - - /** - * loop the groups of equations present at the same iterations - */ - for (size_t g = 0; g < info.equationGroups.size(); g++) { - - const HessianWithLoopsEquationGroupInfo& infog = info.equationGroups[g]; - - /*************************************************************** - * indexed - indexed - */ - for (const pairss& it : group.indexedIndexed) { - size_t tapeJ1 = it.first; - size_t tapeJ2 = it.second; - - itPos = infog.indexedIndexedPositions.find(it); - if (itPos != infog.indexedIndexedPositions.end()) { - const std::vector& positions = itPos->second; - - addContribution(indexedLoopResults, hessLE, - createReverseMode2Contribution(handler, group, - positions, infog.hess.at(tapeJ1).at(tapeJ2), tx1, - iterationIndexOp, - jrow2CompressedLoc)); - } - } - - /** - * indexed - non-indexed - */ - for (const pairss& it : group.indexedNonIndexed) { - size_t tapeJ1 = it.first; - size_t tapeJ2 = it.second; - - itPos = infog.indexedNonIndexedPositions.find(it); - if (itPos != infog.indexedNonIndexedPositions.end()) { - const std::vector& positions = itPos->second; - - addContribution(indexedLoopResults, hessLE, - createReverseMode2Contribution(handler, group, - positions, infog.hess.at(tapeJ1).at(tapeJ2), tx1, - iterationIndexOp, - jrow2CompressedLoc)); - } - } - - /** - * indexed - temporary - */ - for (const pairss& it : group.indexedTemp) { - size_t tapeJ1 = it.first; - size_t j2 = it.second; - - itPos = infog.indexedTempPositions.find(it); - if (itPos != infog.indexedTempPositions.end()) { - const std::vector& positions = itPos->second; - const set& ks = infog.indexedTempEvals.at(it); - - CGBase val = Base(0); - for (size_t k : ks) { - size_t tapeK = lModel.getTempIndepIndexes(k)->tape; - val += infog.hess.at(tapeJ1).at(tapeK) * dzDx.at(k).at(j2); - } - - addContribution(indexedLoopResults, hessLE, - createReverseMode2Contribution(handler, group, - positions, val, tx1, - iterationIndexOp, - jrow2CompressedLoc)); - } - } - - - /*************************************************************** - * non-indexed - indexed - */ - for (const pairss& it : group.nonIndexedIndexed) { - size_t tapeJ1 = it.first; - size_t tapeJ2 = it.second; - - itPos = infog.nonIndexedIndexedPositions.find(it); - if (itPos != infog.nonIndexedIndexedPositions.end()) { - const std::vector& positions = itPos->second; - - addContribution(indexedLoopResults, hessLE, - createReverseMode2Contribution(handler, group, - positions, infog.hess.at(tapeJ1).at(tapeJ2), tx1, - iterationIndexOp, - jrow2CompressedLoc)); - } - } - - /*************************************************************** - * temporary - indexed - * - * d f_i . d x_k1 - * d x_l2 d z_k1 d x_j1 - */ - for (const pairss& it : group.tempIndexed) { - size_t j1 = it.first; - size_t tapeJ2 = it.second; - - itPos = infog.tempIndexedPositions.find(it); - if (itPos != infog.tempIndexedPositions.end()) { - const std::vector& positions = itPos->second; - const set& ks = infog.indexedTempEvals.at(pairss(tapeJ2, j1)); - - CGBase val = Base(0); - for (size_t k : ks) { - size_t tapeK = lModel.getTempIndepIndexes(k)->tape; - val += infog.hess.at(tapeK).at(tapeJ2) * dzDx.at(k).at(j1); - } - - addContribution(indexedLoopResults, hessLE, - createReverseMode2Contribution(handler, group, - positions, val, tx1, - iterationIndexOp, - jrow2CompressedLoc)); - } - } - } - - /******************************************************************* - * contributions to a constant location - */ - for (const pairss& orig : group.nonIndexedNonIndexed) { - size_t e = info.nonIndexedNonIndexedPosition.at(orig); - - size_t j1 = orig.first; - size_t j2 = orig.second; - const LoopPosition* posJ1 = lModel.getNonIndexedIndepIndexes(j1); - const LoopPosition* posJ2 = lModel.getNonIndexedIndepIndexes(j2); - - // location - LinearIndexPattern* pattern = new LinearIndexPattern(0, 0, 0, e); - handler.manageLoopDependentIndexPattern(pattern); - - /** - * non-indexed - non-indexed - */ - CGBase hessVal = Base(0); - - /** - * loop the groups of equations present at the same iterations - */ - for (size_t g = 0; g < info.equationGroups.size(); g++) { - const IterEquationGroup& eqGroup = lModel.getEquationsGroups()[g]; - set iterations; - set_intersection(group.iterations.begin(), group.iterations.end(), - eqGroup.iterations.begin(), eqGroup.iterations.end(), - std::inserter(iterations, iterations.begin())); - - CGBase gHessVal = Base(0); - const HessianWithLoopsEquationGroupInfo& infog = info.equationGroups[g]; - - if (infog.nonIndexedNonIndexedEvals.find(orig) != infog.nonIndexedNonIndexedEvals.end()) { - gHessVal = infog.hess.at(posJ1->tape).at(posJ2->tape); - } - - /** - * non-indexed - temporary - */ - const auto itNT = infog.nonIndexedTempEvals.find(orig); - if (itNT != infog.nonIndexedTempEvals.end()) { - const set& ks = itNT->second; - - for (size_t k : ks) { - size_t tapeK = lModel.getTempIndepIndexes(k)->tape; - gHessVal += infog.hess.at(posJ1->tape).at(tapeK) * dzDx.at(k).at(j2); - } - } - - /** - * temporary - non-indexed - * - * d f_i . d x_k1 - * d x_j2 d z_k1 d x_j1 - */ - const auto itTN = infog.tempNonIndexedEvals.find(orig); - if (itTN != infog.tempNonIndexedEvals.end()) { - const set& ks = itTN->second; - - for (size_t k1 : ks) { - size_t tapeK = lModel.getTempIndepIndexes(k1)->tape; - gHessVal += infog.hess.at(tapeK).at(posJ2->tape) * dzDx.at(k1).at(j1); - } - } - - /** - * temporary - temporary - */ - const auto itTT = infog.tempTempEvals.find(orig); - if (itTT != infog.tempTempEvals.end()) { - const map >& k1k2 = itTT->second; - - CGBase sum = Base(0); - - for (const auto& itzz : k1k2) { - size_t k1 = itzz.first; - const set& k2s = itzz.second; - size_t tapeK1 = lModel.getTempIndepIndexes(k1)->tape; - - CGBase tmp = Base(0); - for (size_t k2 : k2s) { - size_t tapeK2 = lModel.getTempIndepIndexes(k2)->tape; - - tmp += infog.hess.at(tapeK1).at(tapeK2) * dzDx.at(k2).at(j2); - } - - sum += tmp * dzDx.at(k1).at(j1); - } - - gHessVal += sum; - } - - if (iterations.size() != group.iterations.size()) { - CGBase v = createReverseMode2Contribution(handler, group, - *pattern, iterations, - gHessVal, - *info.iterationIndexOp, - group.ifElses); - addContribution(indexedLoopResults, hessLE, make_pair(v, (IndexPattern*) nullptr)); - jrow2CompressedLoc[j1].insert(e); - } else { - hessVal += gHessVal; - } - } - - /** - * temporary - temporary - */ - const auto itTT2 = info.nonLoopNonIndexedNonIndexed.find(orig); - if (itTT2 != info.nonLoopNonIndexedNonIndexed.end()) { - hessVal += info.dzDxx.at(j1).at(j2); // it is already the sum of ddz / dx_j1 dx_j2 - } - - hessVal *= tx1; - - // place the result - if (!hessVal.isIdenticalZero()) { - addContribution(indexedLoopResults, hessLE, make_pair(hessVal, (IndexPattern*) pattern)); - - jrow2CompressedLoc[j1].insert(e); - } - } - - indexedLoopResults.resize(hessLE); - - return indexedLoopResults; -} - -/** - * Auxiliary structure - */ -struct Reverse2Jrow2Iter { - size_t jrow; - std::set iterations; - - inline Reverse2Jrow2Iter() { - } - - inline Reverse2Jrow2Iter(size_t row, - const std::set& iters) : - jrow(row), - iterations(iters) { - } -}; - -inline bool operator<(const Reverse2Jrow2Iter& l, const Reverse2Jrow2Iter& r) { - if (l.jrow < r.jrow) - return true; - else if (l.jrow > r.jrow) - return false; - - return compare(l.iterations, r.iterations) == -1; -} - -/** - * Create groups with the same contributions at the same Hessian rows - */ -template -inline std::map, std::set > groupHessianRowsByContrib(const loops::HessianWithLoopsInfo& info, - size_t n, - std::map > >& indexedIndexed2jrow2Iter, - std::map > >& indexedNonIndexed2jrow2Iter, - std::map > >& indexedTemp2jrow2Iter, - std::map > >& nonIndexedIndexed2jrow2Iter, - std::map > >& tempIndexed2jrow2Iter) { - using namespace std; - - size_t nIterations = info.model->getIterationCount(); - - /** - * determine the contributions to each Hessian row - */ - std::vector > jrows(n); - - for (size_t g = 0; g < info.equationGroups.size(); g++) { - const HessianWithLoopsEquationGroupInfo& infog = info.equationGroups[g]; - - // indexed-indexed - for (const auto& it : infog.indexedIndexedPositions) { - map >& jrow2Iter = indexedIndexed2jrow2Iter[it.first]; - const std::vector& positions = it.second; - for (size_t iter = 0; iter < nIterations; iter++) { - if (positions[iter].count > 0) { - jrows[positions[iter].row].indexedIndexed.insert(it.first); - jrow2Iter[positions[iter].row].insert(iter); - } - } - } - - // indexed - non-indexed - for (const auto& it : infog.indexedNonIndexedPositions) { - map >& jrow2Iter = indexedNonIndexed2jrow2Iter[it.first]; - const std::vector& positions = it.second; - for (size_t iter = 0; iter < nIterations; iter++) { - if (positions[iter].count > 0) { - jrows[positions[iter].row].indexedNonIndexed.insert(it.first); - jrow2Iter[positions[iter].row].insert(iter); - } - } - } - - // indexed - temporary - for (const auto& it : infog.indexedTempPositions) { - map >& jrow2Iter = indexedTemp2jrow2Iter[it.first]; - const std::vector& positions = it.second; - for (size_t iter = 0; iter < nIterations; iter++) { - if (positions[iter].count > 0) { - jrows[positions[iter].row].indexedTemp.insert(it.first); - jrow2Iter[positions[iter].row].insert(iter); - } - } - } - - // non-indexed - indexed - for (const auto& it : infog.nonIndexedIndexedPositions) { - map >& jrow2Iter = nonIndexedIndexed2jrow2Iter[it.first]; - const std::vector& positions = it.second; - for (size_t iter = 0; iter < nIterations; iter++) { - if (positions[iter].count > 0) { - jrows[positions[iter].row].nonIndexedIndexed.insert(it.first); - jrow2Iter[positions[iter].row].insert(iter); - } - } - } - - // temporary - indexed - for (const auto& it : infog.tempIndexedPositions) { - map >& jrow2Iter = tempIndexed2jrow2Iter[it.first]; - const std::vector& positions = it.second; - for (size_t iter = 0; iter < nIterations; iter++) { - if (positions[iter].count > 0) { - jrows[positions[iter].row].tempIndexed.insert(it.first); - jrow2Iter[positions[iter].row].insert(iter); - } - } - } - } - - // non-indexed - non-indexed - for (const auto& orig2PosIt : info.nonIndexedNonIndexedPosition) { - size_t j1 = orig2PosIt.first.first; - jrows[j1].nonIndexedNonIndexed.insert(orig2PosIt.first); - } - - /** - * group rows with the same contribution terms - */ - map, set > contrib2jrows; - for (size_t j = 0; j < n; j++) { - if (!jrows[j].empty()) - contrib2jrows[jrows[j]].insert(j); - } - - return contrib2jrows; -} - -/** - * Create subgroups from groups with the same contributions at the - * same Hessian rows. Each subgroup has a sub-set of the group's - * contributions which have the same relations between Hessian row index - * and set of iteration indexes. - */ -template -inline void subgroupHessianRowsByContrib(const HessianWithLoopsInfo& info, - const HessianTermContrib& c, - const std::set& jrows, - const std::map > >& indexedIndexed2jrow2Iter, - const std::map > >& indexedNonIndexed2jrow2Iter, - const std::map > >& indexedTemp2jrow2Iter, - const std::map > >& nonIndexedIndexed2jrow2Iter, - const std::map > >& tempIndexed2jrow2Iter, - SmartVectorPointer >& subGroups) { - using namespace std; - - map > contribs; - - set::const_iterator it; - map >::const_iterator itJrow2Iter; - - // indexed - indexed - for (pairss pos : c.indexedIndexed) { - map > jrow2Iter = filterBykeys(indexedIndexed2jrow2Iter.at(pos), jrows); - for (itJrow2Iter = jrow2Iter.begin(); itJrow2Iter != jrow2Iter.end(); ++itJrow2Iter) { - Reverse2Jrow2Iter k(itJrow2Iter->first, itJrow2Iter->second); - contribs[k].indexedIndexed.insert(pos); - } - } - - // indexed - non-indexed - for (pairss pos : c.indexedNonIndexed) { - map > jrow2Iter = filterBykeys(indexedNonIndexed2jrow2Iter.at(pos), jrows); - for (itJrow2Iter = jrow2Iter.begin(); itJrow2Iter != jrow2Iter.end(); ++itJrow2Iter) { - Reverse2Jrow2Iter k(itJrow2Iter->first, itJrow2Iter->second); - contribs[k].indexedNonIndexed.insert(pos); - } - } - - // indexed - temporary - for (pairss pos : c.indexedTemp) { - map > jrow2Iter = filterBykeys(indexedTemp2jrow2Iter.at(pos), jrows); - for (itJrow2Iter = jrow2Iter.begin(); itJrow2Iter != jrow2Iter.end(); ++itJrow2Iter) { - Reverse2Jrow2Iter k(itJrow2Iter->first, itJrow2Iter->second); - contribs[k].indexedTemp.insert(pos); - } - } - - // non-indexed - indexed - for (pairss pos : c.nonIndexedIndexed) { - map > jrow2Iter = filterBykeys(nonIndexedIndexed2jrow2Iter.at(pos), jrows); - for (itJrow2Iter = jrow2Iter.begin(); itJrow2Iter != jrow2Iter.end(); ++itJrow2Iter) { - Reverse2Jrow2Iter k(itJrow2Iter->first, itJrow2Iter->second); - contribs[k].nonIndexedIndexed.insert(pos); - } - } - - // non-indexed - non-indexed - if (!c.nonIndexedNonIndexed.empty()) { - set allIters; - size_t nIterations = info.model->getIterationCount(); - for (size_t iter = 0; iter < nIterations; iter++) - allIters.insert(allIters.end(), iter); - - for (pairss pos : c.nonIndexedNonIndexed) { - Reverse2Jrow2Iter k(pos.first, allIters); - contribs[k].nonIndexedNonIndexed.insert(pos); - } - } - - // temporary - indexed - for (pairss pos : c.tempIndexed) { - map > jrow2Iter = filterBykeys(tempIndexed2jrow2Iter.at(pos), jrows); - for (itJrow2Iter = jrow2Iter.begin(); itJrow2Iter != jrow2Iter.end(); ++itJrow2Iter) { - Reverse2Jrow2Iter k(itJrow2Iter->first, itJrow2Iter->second); - contribs[k].tempIndexed.insert(pos); - } - } - - /** - * - */ - map, HessianRowGroup*> c2subgroups; // add pair > here - - for (const auto& itK2C : contribs) { - const Reverse2Jrow2Iter& jrow2Iters = itK2C.first; - const HessianTermContrib& hc = itK2C.second; - - const auto its = c2subgroups.find(hc); - if (its != c2subgroups.end()) { - HessianRowGroup* sg = its->second; - sg->jRow2Iterations[jrow2Iters.jrow] = jrow2Iters.iterations; - sg->iterations.insert(jrow2Iters.iterations.begin(), jrow2Iters.iterations.end()); - } else { - HessianRowGroup* sg = new HessianRowGroup(hc, jrow2Iters); - subGroups.push_back(sg); - c2subgroups[hc] = sg; - } - } -} - -template -std::pair, IndexPattern*> createReverseMode2Contribution(CodeHandler& handler, - HessianRowGroup& group, - const std::vector& positions, - const CG& ddfdxdx, - const CG& tx1, - IndexOperationNode& iterationIndexOp, - std::map >& jrow2CompressedLoc) { - using namespace std; - - if (ddfdxdx.isIdenticalZero()) { - return make_pair(ddfdxdx, (IndexPattern*) nullptr); - } - - /** - * Determine index pattern - */ - std::map iteration2pos; - - // combine iterations with the same number of additions - map > locations; - for (size_t iter : group.iterations) { - size_t c = positions[iter].count; - if (c > 0) { - locations[c][iter] = positions[iter].location; - iteration2pos[iter] = positions[iter].location; - jrow2CompressedLoc[positions[iter].row].insert(positions[iter].location); - } - } - - if (locations.empty()) { - return make_pair(CG(Base(0)), (IndexPattern*) nullptr); - } - - map > results; - - // generate the index pattern for the Hessian compressed element - for (const auto& countIt : locations) { - size_t count = countIt.first; - - CG val = ddfdxdx; - for (size_t c = 1; c < count; c++) - val += ddfdxdx; - - results[count] = val * tx1; - } - - if (results.size() == 1 && locations.begin()->second.size() == group.iterations.size()) { - // same expression present in all iterations - - // generate the index pattern for the Hessian compressed element - IndexPattern* pattern = IndexPattern::detect(locations.begin()->second); - handler.manageLoopDependentIndexPattern(pattern); - - return make_pair(results.begin()->second, pattern); - - } else { - /** - * must create a conditional element so that this - * contribution to the Hessian is only evaluated at the - * relevant iterations - */ - map > branches; - - // try to find an existing if-else where these operations can be added - for (const auto& countIt : locations) { - size_t count = countIt.first; - IfBranchData branch(results[count], countIt.second); - branches[count] = branch; - } - - CG v = createConditionalContribution(handler, - branches, - positions.size() - 1, - group.iterations.size(), - iterationIndexOp, - group.ifElses); - - return make_pair(v, (IndexPattern*) nullptr); - } - -} - -/** - * Hessian contribution to a constant location - */ -template -CG createReverseMode2Contribution(CodeHandler& handler, - HessianRowGroup& group, - LinearIndexPattern& pattern, - const std::set& iterations, - const CG& ddfdxdx, - IndexOperationNode& iterationIndexOp, - std::vector >& ifElses) { - using namespace std; - - if (ddfdxdx.isIdenticalZero()) { - return ddfdxdx; - } - - CPPADCG_ASSERT_UNKNOWN(pattern.getLinearSlopeDy() == 0); // must be a constant index - - if (iterations.size() == group.iterations.size()) { - // same expression present in all iterations - return ddfdxdx; - - } else { - /** - * must create a conditional element so that this - * contribution to the Hessian is only evaluated at the - * relevant iterations - */ - return createConditionalContribution(handler, pattern, - iterations, *group.iterations.rbegin(), - ddfdxdx, iterationIndexOp, - ifElses); - } -} - -/** - * Group of contributions to an Hessian - */ -template -class HessianTermContrib { -public: - // (tapeJ1, tapeJ2) - std::set indexedIndexed; - // (tapeJ1, tapeJ2(j2)) - std::set indexedNonIndexed; - // (tapeJ1, j2) - std::set indexedTemp; - // (tapeJ1(j1), tapeJ2) - std::set nonIndexedIndexed; - //(j1, j2) - std::set nonIndexedNonIndexed; - // (j1, tapeJ2) - std::set tempIndexed; - -public: - - inline bool empty() const { - return indexedIndexed.empty() && indexedNonIndexed.empty() && indexedTemp.empty() && - nonIndexedIndexed.empty() && nonIndexedNonIndexed.empty() && - tempIndexed.empty(); - } - - inline size_t size() const { - return indexedIndexed.size() + indexedNonIndexed.size() + indexedTemp.size() + - nonIndexedIndexed.size() + nonIndexedNonIndexed.size() + - tempIndexed.size(); - } -}; - -template -bool operator<(const HessianTermContrib& l, const HessianTermContrib& r) { - int c = compare(l.indexedIndexed, r.indexedIndexed); - if (c != 0) return c == -1; - c = compare(l.indexedNonIndexed, r.indexedNonIndexed); - if (c != 0) return c == -1; - c = compare(l.indexedTemp, r.indexedTemp); - if (c != 0) return c == -1; - c = compare(l.nonIndexedIndexed, r.nonIndexedIndexed); - if (c != 0) return c == -1; - c = compare(l.nonIndexedNonIndexed, r.nonIndexedNonIndexed); - if (c != 0) return c == -1; - c = compare(l.tempIndexed, r.tempIndexed); - if (c != 0) return c == -1; - return false; -} - -/** - * Group of contributions to an Hessian with the same relation between - * Hessian rows and set of iterations - */ -template -class HessianRowGroup : public HessianTermContrib { -public: - // all the required iterations for each jrow - std::map > jRow2Iterations; - // all iterations - std::set iterations; - // if-else branches - std::vector > ifElses; -public: - - inline HessianRowGroup(const HessianTermContrib& c, - const Reverse2Jrow2Iter& jrow2Iters) : - HessianTermContrib(c), - iterations(jrow2Iters.iterations) { - jRow2Iterations[jrow2Iters.jrow] = jrow2Iters.iterations; - } -}; - -} // END loops namespace - -template -void ModelCSourceGen::generateFunctionNameLoopRev2(std::ostringstream& cache, - const LoopModel& loop, - size_t g) { - generateFunctionNameLoopRev2(cache, _name, loop, g); -} - -template -void ModelCSourceGen::generateFunctionNameLoopRev2(std::ostringstream& cache, - const std::string& modelName, - const LoopModel& loop, - size_t g) { - cache << modelName << "_" << FUNCTION_SPARSE_REVERSE_TWO << - "_loop" << loop.getLoopId() << "_g" << g; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/save_files_model_library_processor.hpp b/ct_core/include/ct/external/cppad/cg/model/save_files_model_library_processor.hpp deleted file mode 100644 index 64d9c3b8d..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/save_files_model_library_processor.hpp +++ /dev/null @@ -1,84 +0,0 @@ -#ifndef CPPAD_CG_SAVE_FILES_MODEL_LIBRARY_PROCESSOR_INCLUDED -#define CPPAD_CG_SAVE_FILES_MODEL_LIBRARY_PROCESSOR_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Saves source code generated by a model library source code generator to - * the file system. This is typically used for debugging purposes. - * - * @author Joao Leal - */ -template -class SaveFilesModelLibraryProcessor : public ModelLibraryProcessor { -public: - - inline SaveFilesModelLibraryProcessor(ModelLibraryCSourceGen& modelLibraryHelper) : - ModelLibraryProcessor(modelLibraryHelper) { - } - - inline virtual ~SaveFilesModelLibraryProcessor() { - } - - inline void saveSources() { - saveSourcesTo("cppadcg_sources"); - } - - inline void saveSourcesTo(const std::string& sourcesFolder) { - - auto saveFile = [&](const std::string filename, const std::string& source){ - std::ofstream sourceFile; - std::string file = system::createPath(sourcesFolder, filename); - sourceFile.open(file.c_str()); - sourceFile << source; - sourceFile.close(); - }; - - system::createFolder(sourcesFolder); - - const std::map*>& models = this->modelLibraryHelper_->getModels(); - - for (const auto& itm : models) { - const std::map& sources = this->getSources(*itm.second); - - for (const auto& it : sources) { - saveFile(it.first, it.second); - } - } - - for (const auto& it : this->modelLibraryHelper_->getLibrarySources()) { - saveFile(it.first, it.second); - } - - for (const auto& it : this->modelLibraryHelper_->getCustomSources()) { - saveFile(it.first, it.second); - } - } - - inline static void saveLibrarySourcesTo(ModelLibraryCSourceGen& modelLibraryHelper, - const std::string& sourcesFolder) { - SaveFilesModelLibraryProcessor s(modelLibraryHelper); - s.saveSourcesTo(sourcesFolder); - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/system/linux_system.hpp b/ct_core/include/ct/external/cppad/cg/model/system/linux_system.hpp deleted file mode 100644 index 4acde18bb..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/system/linux_system.hpp +++ /dev/null @@ -1,368 +0,0 @@ -#ifndef CPPAD_CG_LINUX_SYSTEM_INCLUDED -#define CPPAD_CG_LINUX_SYSTEM_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#if CPPAD_CG_SYSTEM_LINUX -#include -#include -#include -#include - -namespace CppAD { -namespace cg { - -/** - * Linux system dependent functions - */ -namespace system { - -namespace { - -/** - * Utility class used to close automatically file descriptors - */ -class FDHandler { -public: - int fd; - bool closed; -public: - - inline FDHandler() : fd(0), closed(true) { - } - - inline explicit FDHandler(int fd) : fd(fd), closed(false) { - } - - inline void close() { - if (!closed) { - ::close(fd); - closed = true; - } - } - - inline ~FDHandler() { - close(); - } -}; - -/** - * Utility class for pipes - */ -class PipeHandler { -public: - FDHandler read; - FDHandler write; -public: - - inline void create() { - int fd[2]; /** file descriptors used to communicate between processes*/ - if (pipe(fd) < 0) { - throw CGException("Failed to create pipe"); - } - read.fd = fd[0]; - read.closed = false; - write.fd = fd[1]; - write.closed = false; - } -}; - -} - -template -const std::string SystemInfo::DYNAMIC_LIB_EXTENSION = ".so"; - -template -const std::string SystemInfo::STATIC_LIB_EXTENSION = ".a"; - -inline std::string getWorkingDirectory() { - char buffer[1024]; - - char* ret = getcwd(buffer, 1024); - if (ret == nullptr) { - const char* error = strerror(errno); - throw CGException("Failed to get current working directory: ", error); - } - - return buffer; -} - -inline void createFolder(const std::string& folder) { - int ret = mkdir(folder.c_str(), 0755); - if (ret == -1) { - if (errno != EEXIST) { - const char* error = strerror(errno); - throw CGException("Failed to create directory '", folder + "': ", error); - } - } -} - -inline std::string createPath(const std::string& baseFolder, - const std::string& file) { - if (!baseFolder.empty() && baseFolder.back() == '/') { - return baseFolder + file; - } else { - return baseFolder + "/" + file; - } -} - -inline std::string escapePath(const std::string& path) { - return std::string("\"") + path + "\""; -} - -inline std::string filenameFromPath(const std::string& path) { - size_t pos = path.rfind('/'); - if (pos != std::string::npos) { - if (pos == path.size() - 1) { - return ""; - } else { - return path.substr(pos + 1); - } - } else { - return path; - } -} - -inline std::string directoryFromPath(const std::string& path) { - size_t found = path.find_last_of('/'); - if (found != std::string::npos) { - return path.substr(0, found + 1); - } - return "./"; -} - -inline bool isAbsolutePath(const std::string& path) { - if (path.empty()) - return false; - - return path[0] == '/'; -} - -inline bool isDirectory(const std::string& path) { - struct stat info; - - if (stat(path.c_str(), &info) != 0) { - return false; - } else if (info.st_mode & S_IFDIR) { - return true; - } else { - return false; - } -} - -inline bool isFile(const std::string& path) { - struct stat sts; - errno = 0; - if (stat(path.c_str(), &sts) == 0 && errno == 0) { - return S_ISREG(sts.st_mode); - } else if (errno == ENOENT) { - return false; - } - // could check for an error message... - return false; -} - -inline void callExecutable(const std::string& executable, - const std::vector& args, - std::string* stdOutErrMessage, - const std::string* stdInMessage) { - std::string execName = filenameFromPath(executable); - - PipeHandler pipeMsg; // file descriptors used to communicate between processes - pipeMsg.create(); - - PipeHandler pipeStdOutErr; // file descriptors used to communicate between processes - if(stdOutErrMessage != nullptr) { - pipeStdOutErr.create(); - } - - PipeHandler pipeSrc; - if (stdInMessage != nullptr) { - //Create pipe for piping source to the compiler - pipeSrc.create(); - } - - //Fork the compiler, pipe source to it, wait for the compiler to exit - pid_t pid = fork(); - if (pid < 0) { - throw CGException("Failed to fork process"); - } - - if (pid == 0) { - /*********************************************************************** - * Child process - **********************************************************************/ - pipeMsg.read.close(); - - if (stdInMessage != nullptr) { - pipeSrc.write.close(); // close write end of pipe - // Send pipe input to stdin - close(STDIN_FILENO); - if (dup2(pipeSrc.read.fd, STDIN_FILENO) == -1) { - perror("redirecting stdin"); - exit(EXIT_FAILURE); - } - } - - if(stdOutErrMessage != nullptr) { - pipeStdOutErr.read.close(); // close read end of pipe - - // redirect stdout - if (dup2(pipeStdOutErr.write.fd, STDOUT_FILENO) == -1) { - perror("redirecting stdout"); - exit(EXIT_FAILURE); - } - - // redirect stderr - if (dup2(pipeStdOutErr.write.fd, STDERR_FILENO) == -1) { - perror("redirecting stderr"); - exit(EXIT_FAILURE); - } - } - - auto toCharArray = [](const std::string & args) { - const size_t s = args.size() + 1; - char* args2 = new char[s]; - for (size_t c = 0; c < s - 1; c++) { - args2[c] = args.at(c); - } - args2[s - 1] = '\0'; - return args2; - }; - - std::vector args2(args.size() + 2); - args2[0] = toCharArray(execName); - for (size_t i = 0; i < args.size(); i++) { - args2[i + 1] = toCharArray(args[i]); - } - args2.back() = (char *) nullptr; // END - - int eCode = execv(executable.c_str(), &args2[0]); - - for (size_t i = 0; i < args.size(); i++) { - delete [] args2[i]; - } - - if(stdOutErrMessage != nullptr) { - pipeStdOutErr.write.close(); - } - - if (eCode < 0) { - char buf[512]; - std::string error = executable + ": " + strerror_r(errno, buf, 511); // thread safe - ssize_t size = error.size() + 1; - if (write(pipeMsg.write.fd, error.c_str(), size) != size) { - std::cerr << "Failed to send message to parent process" << std::endl; - } - std::cerr << "*** ERROR: exec failed" << std::endl; - exit(EXIT_FAILURE); - } - - exit(EXIT_SUCCESS); - } - - /*************************************************************************** - * Parent process - **************************************************************************/ - pipeMsg.write.close(); - if(stdOutErrMessage != nullptr) { - pipeStdOutErr.write.close(); - } - - auto readCErrorMsg = []() { - int error = errno; - errno = 0; - char buf[512]; - return std::string(strerror_r(error, buf, 512)); - }; - - std::string writeError; - if (stdInMessage != nullptr) { - // close read end of pipe - pipeSrc.read.close(); - //Pipe source to the executable - ssize_t writeFlag = write(pipeSrc.write.fd, stdInMessage->c_str(), stdInMessage->size()); - if (writeFlag == -1) - writeError = readCErrorMsg() + " "; - pipeSrc.write.close(); - } - - //Wait for the executable to exit - int status; - // Read message from the child - std::ostringstream messageErr; - std::ostringstream messageStdOutErr; - size_t size = 0; - char buffer[128]; - do { - ssize_t n; - if(stdOutErrMessage != nullptr) { - while ((n = read(pipeStdOutErr.read.fd, buffer, sizeof (buffer))) > 0) { - messageStdOutErr.write(buffer, n); - size += n; - if (size > 1e4) break; - } - } - - while ((n = read(pipeMsg.read.fd, buffer, sizeof (buffer))) > 0) { - messageErr.write(buffer, n); - size += n; - if (size > 1e4) break; - } - - if (waitpid(pid, &status, 0) < 0) { - throw CGException("Waitpid failed for pid ", pid, " [", readCErrorMsg(), "]"); - } - } while (!WIFEXITED(status) && !WIFSIGNALED(status)); - - pipeMsg.read.close(); - if(stdOutErrMessage != nullptr) { - pipeStdOutErr.read.close(); - } - - if (!writeError.empty()) { - std::ostringstream s; - s << "Failed to write to pipe"; - if (size > 0) s << ": " << messageErr.str(); - else s << ": " << writeError; - throw CGException(s.str()); - } - - if (WIFEXITED(status)) { - if (WEXITSTATUS(status) != EXIT_SUCCESS) { - std::ostringstream s; - s << "Executable '" << executable << "' (pid " << pid << ") exited with code " << WEXITSTATUS(status); - if (size > 0) s << ": " << messageErr.str(); - throw CGException(s.str()); - } - } else if (WIFSIGNALED(status)) { - std::ostringstream s; - s << "Executable '" << executable << "' (pid " << pid << ") terminated by signal " << WTERMSIG(status); - if (size > 0) s << ": " << messageErr.str(); - throw CGException(s.str()); - } - - if (stdOutErrMessage != nullptr) { - *stdOutErrMessage = messageStdOutErr.str(); - } -} - -} // END system namespace - -} // END cg namespace -} // END CppAD namespace - -#endif -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/system/system.hpp b/ct_core/include/ct/external/cppad/cg/model/system/system.hpp deleted file mode 100644 index 072bc3f0e..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/system/system.hpp +++ /dev/null @@ -1,110 +0,0 @@ -#ifndef CPPAD_CG_SYSTEM_INCLUDED -#define CPPAD_CG_SYSTEM_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * System dependent functions - */ -namespace system { - -template -class SystemInfo { -public: - static const std::string DYNAMIC_LIB_EXTENSION; - static const std::string STATIC_LIB_EXTENSION; -}; - -inline std::string getWorkingDirectory(); - -/** - * creates a new folder (system dependent) - * - * @param folder the path to the folder - * @throws CGException on failure to create the folder - */ -inline void createFolder(const std::string& folder); - -/** - * Creates a new path (system dependent) - * - * @param baseFolder the path to the base folder - * @param file the file or folder name inside the base folder - * @return the new path - */ -inline std::string createPath(const std::string& baseFolder, - const std::string& file); - -/** - * Escapes a file or folder path (system dependent) - * - * @param path the file/folder path - * @return the escaped file/folder path - */ -inline std::string escapePath(const std::string& path); - -inline std::string filenameFromPath(const std::string& path); - -inline std::string directoryFromPath(const std::string& path); - -/** - * Determines if a path is absolute. - * - * @param path the path - * @return true if it is absolute, false if it is relative - */ -inline bool isAbsolutePath(const std::string& path); - -/** - * Checks if a path exists and is a directory - * - * @param path the path - * @return true if the path exists and it is a directory - */ -inline bool isDirectory(const std::string& path); - -/** - * Checks if a path exists and is a file - * - * @param path the path - * @return true if the path exists and it is a file - */ -inline bool isFile(const std::string& path); - -/** - * Calls an external executable (system dependent). - * In the case of an error during execution an exception will be thrown. - * - * @param executable the executable path - * @param args the command line arguments to the executable - * @param stdOutErrMessage standard output and standard error message - * from the executable - * @param stdInMessage information to pass as standard input to the executable - * @throws CGException on failure to call the executable - */ -inline void callExecutable(const std::string& executable, - const std::vector& args, - std::string* stdOutErrMessage = nullptr, - const std::string* stdInMessage = nullptr); - -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/model/threadpool/multi_threading_type.hpp b/ct_core/include/ct/external/cppad/cg/model/threadpool/multi_threading_type.hpp deleted file mode 100644 index 100bbc7da..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/threadpool/multi_threading_type.hpp +++ /dev/null @@ -1,30 +0,0 @@ -#ifndef CPPAD_CG_MULTITHREADINGTYPE_INCLUDED -#define CPPAD_CG_MULTITHREADINGTYPE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -enum class MultiThreadingType { - NONE, // no multithreading - OPENMP, // using the OpenMP library (does not work on dynamically loaded model libraries) - PTHREADS // using the PThreads library -}; - -} -} - -#endif diff --git a/ct_core/include/ct/external/cppad/cg/model/threadpool/openmp_c.hpp b/ct_core/include/ct/external/cppad/cg/model/threadpool/openmp_c.hpp deleted file mode 100644 index cfba04dbb..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/threadpool/openmp_c.hpp +++ /dev/null @@ -1,76 +0,0 @@ -const char CPPADCG_OPENMP_C_FILE[] = R"*=*(/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include -#include - -enum ScheduleStrategy {SCHED_STATIC = 1, - SCHED_DYNAMIC = 2, - SCHED_GUIDED = 3 - }; - -static volatile int cppadcg_openmp_enabled = 1; // false -static volatile int cppadcg_openmp_verbose = 1; // false -static volatile unsigned int cppadcg_openmp_n_threads = 2; - -static enum ScheduleStrategy schedule_strategy = SCHED_DYNAMIC; - - -void cppadcg_openmp_set_disabled(int disabled) { - cppadcg_openmp_enabled = !disabled; -} - -int cppadcg_openmp_is_disabled() { - return !cppadcg_openmp_enabled; -} - -void cppadcg_openmp_set_verbose(int v) { - cppadcg_openmp_verbose = v; -} - -int cppadcg_openmp_is_verbose() { - return cppadcg_openmp_verbose; -} - -void cppadcg_openmp_set_threads(unsigned int n) { - if(n <= 0) - n = 1; - cppadcg_openmp_n_threads = n; -} - -unsigned int cppadcg_openmp_get_threads() { - return cppadcg_openmp_n_threads; -} - -void cppadcg_openmp_set_scheduler_strategy(enum ScheduleStrategy s) { - schedule_strategy = s; -} - -enum ScheduleStrategy cppadcg_openmp_get_scheduler_strategy() { - return schedule_strategy; -} - -void cppadcg_openmp_apply_scheduler_strategy() { - if (schedule_strategy == SCHED_DYNAMIC) { - omp_set_schedule(omp_sched_dynamic, 1); - } else if (schedule_strategy == SCHED_GUIDED) { - omp_set_schedule(omp_sched_guided, 0); - } else { - omp_set_schedule(omp_sched_static, 0); - } -})*=*"; - -const size_t CPPADCG_OPENMP_C_FILE_SIZE = 2066; - diff --git a/ct_core/include/ct/external/cppad/cg/model/threadpool/openmp_h.hpp b/ct_core/include/ct/external/cppad/cg/model/threadpool/openmp_h.hpp deleted file mode 100644 index ddfe7e42b..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/threadpool/openmp_h.hpp +++ /dev/null @@ -1,56 +0,0 @@ -const char CPPADCG_OPENMP_H_FILE[] = R"*=*(#ifndef CPPADCG_OPENMP_H -#define CPPADCG_OPENMP_H -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ -#ifdef __cplusplus -extern "C" { -#endif - -enum ScheduleStrategy {SCHED_STATIC = 1, // omp_sched_static - SCHED_DYNAMIC = 2, // omp_sched_dynamic with chunk size 1 - SCHED_GUIDED = 3 // omp_sched_guided - }; - - -void cppadcg_openmp_set_threads(unsigned int n); - -unsigned int cppadcg_openmp_get_threads(); - - -void cppadcg_openmp_set_scheduler_strategy(enum ScheduleStrategy s); - -enum ScheduleStrategy cppadcg_openmp_get_scheduler_strategy(); - -void cppadcg_openmp_apply_scheduler_strategy(); - - -void cppadcg_openmp_set_verbose(int v); - -int cppadcg_openmp_is_verbose(); - - -void cppadcg_openmp_set_disabled(int disabled); - -int cppadcg_openmp_is_disabled(); - - -#ifdef __cplusplus -} -#endif - -#endif)*=*"; - -const size_t CPPADCG_OPENMP_H_FILE_SIZE = 1413; - diff --git a/ct_core/include/ct/external/cppad/cg/model/threadpool/pthread_pool_c.hpp b/ct_core/include/ct/external/cppad/cg/model/threadpool/pthread_pool_c.hpp deleted file mode 100644 index fdcf29e8f..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/threadpool/pthread_pool_c.hpp +++ /dev/null @@ -1,1419 +0,0 @@ -const char CPPADCG_PTHREAD_POOL_C_FILE[] = R"*=*(/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Authors: Johan Hanssen Seferidis, Joao Leal - */ - -/** - * This file was adapted by Joao Leal from - * https://github.com/Pithikos/C-Thread-Pool/blob/master/thpool.c - */ - -#include -#include -#include -#include -#include -#include -#if defined(__linux__) -#include -#include -#include -#define __USE_GNU /* required before including resource.h */ -#include -#endif - -enum ScheduleStrategy {SCHED_STATIC = 1, - SCHED_DYNAMIC = 2, - SCHED_GUIDED = 3 - }; - -enum ElapsedTimeReference {ELAPSED_TIME_AVG, - ELAPSED_TIME_MIN}; - -typedef struct ThPool ThPool; -typedef void (* thpool_function_type)(void*); - -static ThPool* volatile cppadcg_pool = NULL; -static int cppadcg_pool_n_threads = 2; -static int cppadcg_pool_disabled = 0; // false -static int cppadcg_pool_verbose = 0; // false -static enum ElapsedTimeReference cppadcg_pool_time_update = ELAPSED_TIME_MIN; -static unsigned int cppadcg_pool_time_meas = 10; // default number of time measurements -static float cppadcg_pool_guided_maxgroupwork = 0.75; - -static enum ScheduleStrategy schedule_strategy = SCHED_DYNAMIC; - -/* ==================== INTERNAL HIGH LEVEL API ====================== */ - -static ThPool* thpool_init(int num_threads); - -static int thpool_add_job(ThPool*, - thpool_function_type function, - void* arg, - const float* avgElapsed, - float* elapsed); - -static int thpool_add_jobs(ThPool*, - thpool_function_type functions[], - void* args[], - const float avgElapsed[], - float elapsed[], - const int order[], - int job2Thread[], - int nJobs, - int lastElapsedChanged); - -static void thpool_wait(ThPool*); - -static void thpool_destroy(ThPool*); - -/* ========================== STRUCTURES ============================ */ -/* Binary semaphore */ -typedef struct BSem { - pthread_mutex_t mutex; - pthread_cond_t cond; - int v; -} BSem; - - -/* Job */ -typedef struct Job { - struct Job* prev; /* pointer to previous job */ - thpool_function_type function; /* function pointer */ - void* arg; /* function's argument */ - const float* avgElapsed; /* the last measurement of elapsed time */ - float* elapsed; /* the current elapsed time */ - struct timespec startTime; /* initial time (verbose only) */ - struct timespec endTime; /* final time (verbose only) */ - int id; /* a job identifier used for debugging */ -} Job; - -/* Work group */ -typedef struct WorkGroup { - struct WorkGroup* prev; /* pointer to previous WorkGroup */ - struct Job* jobs; /* jobs */ - int size; /* number of jobs */ - struct timespec startTime; /* initial time (verbose only) */ - struct timespec endTime; /* final time (verbose only) */ -} WorkGroup; - -/* Job queue */ -typedef struct JobQueue { - pthread_mutex_t rwmutex; /* used for queue r/w access */ - Job *front; /* pointer to front of queue */ - Job *rear; /* pointer to rear of queue */ - WorkGroup* group_front; /* previously created work groups (SCHED_STATIC scheduling only)*/ - BSem *has_jobs; /* flag as binary semaphore */ - int len; /* number of jobs in queue */ - float total_time; /* total expected time to complete the work */ - float highest_expected_return; /* the time when the last running thread is expected to request new work */ -} JobQueue; - - -/* Thread */ -typedef struct Thread { - int id; /* friendly id */ - pthread_t pthread; /* pointer to actual thread */ - struct ThPool* thpool; /* access to ThPool */ - WorkGroup* processed_groups; /* processed work groups (verbose only) */ -} Thread; - - -/* Threadpool */ -typedef struct ThPool { - Thread** threads; /* pointer to threads */ - int num_threads; /* total number of threads */ - volatile int num_threads_alive; /* threads currently alive */ - volatile int num_threads_working; /* threads currently working */ - pthread_mutex_t thcount_lock; /* used for thread count etc */ - pthread_cond_t threads_all_idle; /* signal to thpool_wait */ - JobQueue* jobqueue; /* pointer to the job queue */ - volatile int threads_keepalive; -} ThPool; - -/* ========================== PUBLIC API ============================ */ - -void cppadcg_thpool_set_threads(int n) { - cppadcg_pool_n_threads = n; -} - -int cppadcg_thpool_get_threads() { - return cppadcg_pool_n_threads; -} - -void cppadcg_thpool_set_scheduler_strategy(enum ScheduleStrategy s) { - if(cppadcg_pool != NULL) { - pthread_mutex_lock(&cppadcg_pool->jobqueue->rwmutex); - schedule_strategy = s; - pthread_mutex_unlock(&cppadcg_pool->jobqueue->rwmutex); - } else { - // pool not yet created - schedule_strategy = s; - } -} - -enum ScheduleStrategy cppadcg_thpool_get_scheduler_strategy() { - if(cppadcg_pool != NULL) { - enum ScheduleStrategy e; - pthread_mutex_lock(&cppadcg_pool->jobqueue->rwmutex); - e = schedule_strategy; - pthread_mutex_unlock(&cppadcg_pool->jobqueue->rwmutex); - return e; - } else { - // pool not yet created - return schedule_strategy; - } -} - -void cppadcg_thpool_set_disabled(int disabled) { - cppadcg_pool_disabled = disabled; -} - -int cppadcg_thpool_is_disabled() { - return cppadcg_pool_disabled; -} - -void cppadcg_thpool_set_guided_maxgroupwork(float v) { - if(cppadcg_pool != NULL) { - pthread_mutex_lock(&cppadcg_pool->jobqueue->rwmutex); - cppadcg_pool_guided_maxgroupwork = v; - pthread_mutex_unlock(&cppadcg_pool->jobqueue->rwmutex); - } else { - // pool not yet created - cppadcg_pool_guided_maxgroupwork = v; - } -} - -float cppadcg_thpool_get_guided_maxgroupwork() { - if(cppadcg_pool != NULL) { - float r; - pthread_mutex_lock(&cppadcg_pool->jobqueue->rwmutex); - r = cppadcg_pool_guided_maxgroupwork; - pthread_mutex_unlock(&cppadcg_pool->jobqueue->rwmutex); - return r; - } else { - // pool not yet created - return cppadcg_pool_guided_maxgroupwork; - } -} - -unsigned int cppadcg_thpool_get_n_time_meas() { - return cppadcg_pool_time_meas; -} - -void cppadcg_thpool_set_n_time_meas(unsigned int n) { - cppadcg_pool_time_meas = n; -} - -void cppadcg_thpool_set_verbose(int v) { - cppadcg_pool_verbose = v; -} - -enum ElapsedTimeReference cppadcg_thpool_get_time_meas_ref() { - return cppadcg_pool_time_update; -} - -void cppadcg_thpool_set_time_meas_ref(enum ElapsedTimeReference r) { - cppadcg_pool_time_update = r; -} - -int cppadcg_thpool_is_verbose() { - return cppadcg_pool_verbose; -} - -void cppadcg_thpool_prepare() { - if(cppadcg_pool == NULL) { - cppadcg_pool = thpool_init(cppadcg_pool_n_threads); - } -} - -void cppadcg_thpool_add_job(thpool_function_type function, - void* arg, - float* avgElapsed, - float* elapsed) { - if (!cppadcg_pool_disabled) { - cppadcg_thpool_prepare(); - if (cppadcg_pool != NULL) { - thpool_add_job(cppadcg_pool, function, arg, avgElapsed, elapsed); - return; - } - } - - // thread pool not used - (*function)(arg); -} - -void cppadcg_thpool_add_jobs(thpool_function_type functions[], - void* args[], - const float avgElapsed[], - float elapsed[], - const int order[], - int job2Thread[], - int nJobs, - int lastElapsedChanged) { - int i; - if (!cppadcg_pool_disabled) { - cppadcg_thpool_prepare(); - if (cppadcg_pool != NULL) { - thpool_add_jobs(cppadcg_pool, functions, args, avgElapsed, elapsed, order, job2Thread, nJobs, lastElapsedChanged); - return; - } - } - - // thread pool not used - for (i = 0; i < nJobs; ++i) { - (*functions[i])(args[i]); - } -} - -void cppadcg_thpool_wait() { - if(cppadcg_pool != NULL) { - thpool_wait(cppadcg_pool); - } -} - -typedef struct pair_double_int { - float val; - int index; -} pair_double_int; - -static int comparePair(const void* a, const void* b) { - if (((pair_double_int*) a)->val < ((pair_double_int*) b)->val) - return -1; - if (((pair_double_int*) a)->val == ((pair_double_int*) b)->val) - return 0; - return 1; -} - -void cppadcg_thpool_update_order(float refElapsed[], - unsigned int nTimeMeas, - const float elapsed[], - int order[], - int nJobs) { - if(nJobs == 0 || refElapsed == NULL || elapsed == NULL || order == NULL) - return; - - struct pair_double_int elapsedOrder[nJobs]; - int i; - int nonZero = 0; // false - - for(i = 0; i < nJobs; ++i) { - if(elapsed[i] != 0) { - nonZero = 1; - break; - } - } - - if (!nonZero) { - if (cppadcg_pool_verbose) { - fprintf(stdout, "order not updated: all times are zero\n"); - } - return; - } - - if(cppadcg_pool_time_update == ELAPSED_TIME_AVG) { - for (i = 0; i < nJobs; ++i) { - refElapsed[i] = (refElapsed[i] * nTimeMeas + elapsed[i]) / (nTimeMeas + 1); - elapsedOrder[i].val = refElapsed[i]; - elapsedOrder[i].index = i; - } - } else { - // cppadcg_pool_time_update == ELAPSED_TIME_MIN - for (i = 0; i < nJobs; ++i) { - if(nTimeMeas == 0 || elapsed[i] < refElapsed[i]) { - refElapsed[i] = elapsed[i]; - } - elapsedOrder[i].val = refElapsed[i]; - elapsedOrder[i].index = i; - } - } - - qsort(elapsedOrder, nJobs, sizeof(struct pair_double_int), comparePair); - - for (i = 0; i < nJobs; ++i) { - order[elapsedOrder[i].index] = nJobs - i - 1; // descending order - } - - if (cppadcg_pool_verbose) { - fprintf(stdout, "new order (%i values):\n", nTimeMeas + 1); - for (i = 0; i < nJobs; ++i) { - fprintf(stdout, " job id: %i order: %i time: %e s\n", i, order[i], refElapsed[i]); - } - } - -} - -void cppadcg_thpool_shutdown() { - if(cppadcg_pool != NULL) { - thpool_destroy(cppadcg_pool); - cppadcg_pool = NULL; - } -} - -/* ========================== PROTOTYPES ============================ */ - -static void thpool_cleanup(ThPool* thpool); - -static int thread_init(ThPool* thpool, - Thread** thread, - int id); -static void* thread_do(Thread* thread); -static void thread_destroy(Thread* thread); - -static int jobqueue_init(ThPool* thpool); -static void jobqueue_clear(ThPool* thpool); -static void jobqueue_push(JobQueue* queue, - Job* newjob_p); -static void jobqueue_multipush(JobQueue* queue, - Job* newjob[], - int nJobs); -static int jobqueue_push_static_jobs(ThPool* thpool, - Job* newjobs[], - const float avgElapsed[], - int jobs2thread[], - int nJobs, - int lastElapsedChanged); -static WorkGroup* jobqueue_pull(ThPool* thpool, int id); -static void jobqueue_destroy(ThPool* thpool); - -static void bsem_init(BSem *bsem, int value); -static void bsem_reset(BSem *bsem); -static void bsem_post(BSem *bsem); -static void bsem_post_all(BSem *bsem); -static void bsem_wait(BSem *bsem); - - -/* ============================ TIME ============================== */ - -static float get_thread_time(struct timespec* cputime, - int* info) { - *info = clock_gettime(CLOCK_THREAD_CPUTIME_ID, cputime); - if(*info == 0) { - return cputime->tv_sec + cputime->tv_nsec * 1e-9f; - } else { - fprintf(stderr, "failed clock_gettime()\n"); - return 0; - } -} - -static float get_monotonic_time(struct timespec* time, - int* info) { - *info = clock_gettime(CLOCK_MONOTONIC, time); - if(*info == 0) { - return time->tv_sec + time->tv_nsec * 1e-9f; - } else { - fprintf(stderr, "failed clock_gettime()\n"); - return 0; - } -} - -static void get_monotonic_time2(struct timespec* time) { - int info; - info = clock_gettime(CLOCK_MONOTONIC, time); - if(info != 0) { - time->tv_sec = 0; - time->tv_nsec = 0; - fprintf(stderr, "failed clock_gettime()\n"); - } -} - -void timespec_diff(struct timespec* end, - struct timespec* start, - struct timespec* result) { - if ((end->tv_nsec - start->tv_nsec) < 0) { - result->tv_sec = end->tv_sec - start->tv_sec - 1; - result->tv_nsec = end->tv_nsec - start->tv_nsec + 1000000000; - } else { - result->tv_sec = end->tv_sec - start->tv_sec; - result->tv_nsec = end->tv_nsec - start->tv_nsec; - } -} - -/* ========================== THREADPOOL ============================ */ - -/** - * @brief Initialize threadpool - * - * Initializes a threadpool. This function will not return untill all - * threads have initialized successfully. - * - * @example - * - * .. - * threadpool thpool; //First we declare a threadpool - * thpool = thpool_init(4); //then we initialize it to 4 threads - * .. - * - * @param num_threads number of threads to be created in the threadpool - * @return threadpool created threadpool on success, - * NULL on error - */ -struct ThPool* thpool_init(int num_threads) { - if (num_threads < 0) { - num_threads = 0; - } - - if(cppadcg_pool_verbose) { - fprintf(stdout, "thpool_init(): Thread pool created with %i threads\n", num_threads); - } - - if(num_threads == 0) { - cppadcg_pool_disabled = 1; // true - return NULL; - } - - /* Make new thread pool */ - ThPool* thpool; - thpool = (ThPool*) malloc(sizeof(ThPool)); - if (thpool == NULL) { - fprintf(stderr, "thpool_init(): Could not allocate memory for thread pool\n"); - return NULL; - } - thpool->num_threads = num_threads; - thpool->num_threads_alive = 0; - thpool->num_threads_working = 0; - thpool->threads_keepalive = 1; - - /* Initialize the job queue */ - if (jobqueue_init(thpool) == -1) { - fprintf(stderr, "thpool_init(): Could not allocate memory for job queue\n"); - free(thpool); - return NULL; - } - - /* Make threads in pool */ - thpool->threads = (Thread**) malloc(num_threads * sizeof(Thread*)); - if (thpool->threads == NULL) { - fprintf(stderr, "thpool_init(): Could not allocate memory for threads\n"); - jobqueue_destroy(thpool); - free(thpool->jobqueue); - free(thpool); - return NULL; - } - - pthread_mutex_init(&(thpool->thcount_lock), NULL); - pthread_cond_init(&thpool->threads_all_idle, NULL); - - /* Thread init */ - int n; - for (n = 0; n < num_threads; n++) { - thread_init(thpool, &thpool->threads[n], n); - } - - /* Wait for threads to initialize */ - while (thpool->num_threads_alive != num_threads) {} - - return thpool; -} - -/** - * @brief Add work to the job queue - * - * Takes an action and its argument and adds it to the threadpool's job queue. - * If you want to add to work a function with more than one arguments then - * a way to implement this is by passing a pointer to a structure. - * - * NOTICE: You have to cast both the function and argument to not get warnings. - * - * @example - * - * void print_num(int num){ - * printf("%d\n", num); - * } - * - * int main() { - * .. - * int a = 10; - * thpool_add_job(thpool, (void*)print_num, (void*)a); - * .. - * } - * - * @param threadpool threadpool to which the work will be added - * @param function pointer to function to add as work - * @param arg pointer to an argument - * @return 0 on successs, -1 otherwise. - */ -static int thpool_add_job(ThPool* thpool, - thpool_function_type function, - void* arg, - const float* avgElapsed, - float* elapsed) { - Job* newjob; - - newjob = (struct Job*) malloc(sizeof(struct Job)); - if (newjob == NULL) { - fprintf(stderr, "thpool_add_job(): Could not allocate memory for new job\n"); - return -1; - } - - /* add function and argument */ - newjob->function = function; - newjob->arg = arg; - newjob->avgElapsed = avgElapsed; - newjob->elapsed = elapsed; - - /* add job to queue */ - jobqueue_push(thpool->jobqueue, newjob); - - return 0; -} - -static int thpool_add_jobs(ThPool* thpool, - thpool_function_type functions[], - void* args[], - const float avgElapsed[], - float elapsed[], - const int order[], - int job2Thread[], - int nJobs, - int lastElapsedChanged) { - Job* newjobs[nJobs]; - int i; - int j; - - for (i = 0; i < nJobs; ++i) { - newjobs[i] = (Job*) malloc(sizeof(Job)); - if (newjobs[i] == NULL) { - fprintf(stderr, "thpool_add_jobs(): Could not allocate memory for new jobs\n"); - return -1; - } - - j = order != NULL ? order[i] : i; - /* add function and argument */ - newjobs[i]->function = functions[j]; - newjobs[i]->arg = args[j]; - newjobs[i]->id = i; - if (avgElapsed != NULL) - newjobs[i]->avgElapsed = &avgElapsed[j]; - else - newjobs[i]->avgElapsed = NULL; - - if (elapsed != NULL) - newjobs[i]->elapsed = &elapsed[j]; - else - newjobs[i]->elapsed = NULL; - } - - /* add jobs to queue */ - if (schedule_strategy == SCHED_STATIC && avgElapsed != NULL && order != NULL && nJobs > 0 && avgElapsed[0] > 0) { - return jobqueue_push_static_jobs(thpool, newjobs, avgElapsed, job2Thread, nJobs, lastElapsedChanged); - } else { - jobqueue_multipush(thpool->jobqueue, newjobs, nJobs); - return 0; - } -} - -/** - * Split work among the threads evenly considering the elapsed time of each job. - */ -static int jobqueue_push_static_jobs(ThPool* thpool, - Job* newjobs[], - const float avgElapsed[], - int jobs2thread[], - int nJobs, - int lastElapsedChanged) { - float total_duration, target_duration, next_duration, best_duration; - int i, j, iBest; - int added; - int num_threads = thpool->num_threads; - int* n_jobs; - float* durations = NULL; - WorkGroup** groups; - WorkGroup* group; - - if(nJobs < num_threads) - num_threads = nJobs; - - n_jobs = (int*) malloc(num_threads * sizeof(int)); - if (n_jobs == NULL) { - fprintf(stderr, "jobqueue_push_static_jobs(): Could not allocate memory\n"); - return -1; - } - - groups = (WorkGroup**) malloc(num_threads * sizeof(WorkGroup*)); - if (groups == NULL) { - fprintf(stderr, "jobqueue_push_static_jobs(): Could not allocate memory\n"); - return -1; - } - - for (i = 0; i < num_threads; ++i) { - n_jobs[i] = 0; - } - - total_duration = 0; - for (i = 0; i < nJobs; ++i) { - total_duration += avgElapsed[i]; - } - - - if (nJobs > 0 && (lastElapsedChanged || jobs2thread[0] < 0)) { - durations = (float*) malloc(num_threads * sizeof(float)); - if (durations == NULL) { - fprintf(stderr, "jobqueue_push_static_jobs(): Could not allocate memory\n"); - return -1; - } - - for(i = 0; i < num_threads; ++i) { - durations[i] = 0; - } - - // decide in which work group to place each job - target_duration = total_duration / num_threads; - - for (j = 0; j < nJobs; ++j) { - added = 0; - for (i = 0; i < num_threads; ++i) { - next_duration = durations[i] + avgElapsed[j]; - if (next_duration < target_duration) { - durations[i] = next_duration; - n_jobs[i]++; - jobs2thread[j] = i; - added = 1; - break; - } - } - - if (!added) { - best_duration = durations[0] + avgElapsed[j]; - iBest = 0; - for (i = 1; i < num_threads; ++i) { - next_duration = durations[i] + avgElapsed[j]; - if (next_duration < best_duration) { - best_duration = next_duration; - iBest = i; - } - } - durations[iBest] = best_duration; - n_jobs[iBest]++; - jobs2thread[j] = iBest; - } - } - - } else { - // reuse existing information - - for (j = 0; j < nJobs; ++j) { - n_jobs[jobs2thread[j]]++; - } - } - - /** - * create the work groups - */ - for (i = 0; i < num_threads; ++i) { - group = (WorkGroup*) malloc(sizeof(WorkGroup)); - group->size = 0; - group->jobs = (Job*) malloc(n_jobs[i] * sizeof(Job)); - groups[i] = group; - } - for (i = 0; i < num_threads - 1; ++i) { - groups[i]->prev = groups[i + 1]; - } - groups[num_threads - 1]->prev = NULL; - - // place jobs on the work groups - for (j = 0; j < nJobs; ++j) { - i = jobs2thread[j]; - group = groups[i]; - group->jobs[group->size] = *newjobs[j]; // copy - group->size++; - free(newjobs[j]); - } - - if (cppadcg_pool_verbose) { - if (durations != NULL) { - for (i = 0; i < num_threads; ++i) { - fprintf(stdout, "jobqueue_push_static_jobs(): work group %i with %i jobs for %e s\n", i, groups[i]->size, durations[i]); - } - } else { - for (i = 0; i < num_threads; ++i) { - fprintf(stdout, "jobqueue_push_static_jobs(): work group %i with %i jobs\n", i, groups[i]->size); - } - } - } - - /** - * add to the queue - */ - pthread_mutex_lock(&thpool->jobqueue->rwmutex); - - groups[num_threads - 1]->prev = thpool->jobqueue->group_front; - thpool->jobqueue->group_front = groups[0]; - - bsem_post_all(thpool->jobqueue->has_jobs); - - pthread_mutex_unlock(&thpool->jobqueue->rwmutex); - - // clean up - free(durations); - free(n_jobs); - free(groups); - - return 0; -} - -/** - * @brief Wait for all queued jobs to finish - * - * Will wait for all jobs - both queued and currently running to finish. - * Once the queue is empty and all work has completed, the calling thread - * (probably the main program) will continue. - * - * Smart polling is used in wait. The polling is initially 0 - meaning that - * there is virtually no polling at all. If after 1 seconds the threads - * haven't finished, the polling interval starts growing exponentially - * untill it reaches max_secs seconds. Then it jumps down to a maximum polling - * interval assuming that heavy processing is being used in the threadpool. - * - * @example - * - * .. - * threadpool thpool = thpool_init(4); - * .. - * // Add a bunch of work - * .. - * thpool_wait(thpool); - * puts("All added work has finished"); - * .. - * - * @param threadpool the threadpool to wait for - */ -static void thpool_wait(ThPool* thpool) { - pthread_mutex_lock(&thpool->thcount_lock); - while (thpool->jobqueue->len || thpool->jobqueue->group_front || thpool->num_threads_working) { //// PROBLEM HERE!!!! len is not locked!!!! - pthread_cond_wait(&thpool->threads_all_idle, &thpool->thcount_lock); - } - thpool->jobqueue->total_time = 0; - thpool->jobqueue->highest_expected_return = 0; - pthread_mutex_unlock(&thpool->thcount_lock); - - thpool_cleanup(thpool); -} - - -/** - * Called to clean-up after waiting for a thread pool to end the current work. - * It is only required when cppadcg_pool_verbose was enabled. - * - * @param thpool - */ -void thpool_cleanup(ThPool* thpool) { - // for debugging only - - struct timespec diffTime; - int gid = 0; - Thread* thread; - WorkGroup* workGroup; - WorkGroup* workGroupPrev; - - if (!cppadcg_pool_verbose) { - return; - } - - for (int j = 0; j < thpool->num_threads; ++j) { - thread = thpool->threads[j]; - - workGroup = thread->processed_groups; - while (workGroup != NULL) { - timespec_diff(&workGroup->endTime, &workGroup->startTime, &diffTime); - fprintf(stdout, "# Thread %i, Group %i, started at %ld.%.9ld, ended at %ld.%.9ld, elapsed %ld.%.9ld, executed %i jobs\n", - thread->id, gid, workGroup->startTime.tv_sec, workGroup->startTime.tv_nsec, workGroup->endTime.tv_sec, workGroup->endTime.tv_nsec, diffTime.tv_sec, - diffTime.tv_nsec, workGroup->size); - - for (int i = 0; i < workGroup->size; ++i) { - Job* job = &workGroup->jobs[i]; - - timespec_diff(&job->endTime, &job->startTime, &diffTime); - fprintf(stdout, "## Thread %i, Group %i, Job %i, started at %ld.%.9ld, ended at %ld.%.9ld, elapsed %ld.%.9ld\n", - thread->id, gid, job->id, job->startTime.tv_sec, job->startTime.tv_nsec, job->endTime.tv_sec, job->endTime.tv_nsec, diffTime.tv_sec, - diffTime.tv_nsec); - } - - gid++; - - workGroupPrev = workGroup->prev; - - // clean-up - free(workGroup->jobs); - free(workGroup); - - workGroup = workGroupPrev; - } - - thread->processed_groups = NULL; - } -} - -/** - * @brief Destroy the threadpool - * - * This will wait for the currently active threads to finish and then 'kill' - * the whole threadpool to free up memory. - * - * @example - * int main() { - * threadpool thpool1 = thpool_init(2); - * threadpool thpool2 = thpool_init(2); - * .. - * thpool_destroy(thpool1); - * .. - * return 0; - * } - * - * @param threadpool the threadpool to destroy - * @return nothing - */ -static void thpool_destroy(ThPool* thpool) { - /* No need to destory if it's NULL */ - if (thpool == NULL) return; - - volatile int threads_total = thpool->num_threads_alive; - - /* End each thread 's infinite loop */ - thpool->threads_keepalive = 0; - - /* Give one second to kill idle threads */ - double TIMEOUT = 1.0; - time_t start, end; - double tpassed = 0.0; - time(&start); - while (tpassed < TIMEOUT && thpool->num_threads_alive) { - bsem_post_all(thpool->jobqueue->has_jobs); - time(&end); - tpassed = difftime(end, start); - } - - /* Poll remaining threads */ - while (thpool->num_threads_alive) { - bsem_post_all(thpool->jobqueue->has_jobs); - sleep(1); - } - - /* cleanup current work groups */ - thpool_cleanup(thpool); - - /* Job queue cleanup */ - jobqueue_destroy(thpool); - free(thpool->jobqueue); - - /* Deallocs */ - int n; - for (n = 0; n < threads_total; n++) { - thread_destroy(thpool->threads[n]); - } - free(thpool->threads); - free(thpool); - - if(cppadcg_pool_verbose) { - fprintf(stdout, "thpool_destroy(): thread pool destroyed\n"); - } -} - - -/* ============================ THREAD ============================== */ - - -/* Initialize a thread in the thread pool - * - * @param thread address to the pointer of the thread to be created - * @param id id to be given to the thread - * @return 0 on success, -1 otherwise. - */ -static int thread_init(ThPool* thpool, - Thread** thread, - int id) { - - *thread = (Thread*) malloc(sizeof(Thread)); - if (*thread == NULL) { - fprintf(stderr, "thread_init(): Could not allocate memory for thread\n"); - return -1; - } - - (*thread)->thpool = thpool; - (*thread)->id = id; - (*thread)->processed_groups = NULL; - - pthread_create(&(*thread)->pthread, NULL, (void*) thread_do, (*thread)); - pthread_detach((*thread)->pthread); - return 0; -} - -/* What each thread is doing -* -* In principle this is an endless loop. The only time this loop gets interrupted is once -* thpool_destroy() is invoked or the program exits. -* -* @param thread thread that will run this function -* @return nothing -*/ -static void* thread_do(Thread* thread) { - float elapsed; - int info; - struct timespec cputime; - JobQueue* queue; - WorkGroup* workGroup; - Job* job; - thpool_function_type func_buff; - void* arg_buff; - int i; - - /* Set thread name for profiling and debugging */ - char thread_name[128] = {0}; - sprintf(thread_name, "thread-pool-%d", thread->id); - -#if defined(__linux__) - /* Use prctl instead to prevent using _GNU_SOURCE flag and implicit declaration */ - prctl(PR_SET_NAME, thread_name); -#elif defined(__APPLE__) && defined(__MACH__) - pthread_setname_np(thread_name); -#else - fprintf(stderr, "thread_do(): pthread_setname_np is not supported on this system"); -#endif - - /* Assure all threads have been created before starting serving */ - ThPool* thpool = thread->thpool; - - /* Mark thread as alive (initialized) */ - pthread_mutex_lock(&thpool->thcount_lock); - thpool->num_threads_alive += 1; - pthread_mutex_unlock(&thpool->thcount_lock); - - queue = thpool->jobqueue; - - while (thpool->threads_keepalive) { - - bsem_wait(queue->has_jobs); - - if (!thpool->threads_keepalive) { - break; - } - - pthread_mutex_lock(&thpool->thcount_lock); - thpool->num_threads_working++; - pthread_mutex_unlock(&thpool->thcount_lock); - - while (thpool->threads_keepalive) { - /* Read job from queue and execute it */ - pthread_mutex_lock(&queue->rwmutex); - workGroup = jobqueue_pull(thpool, thread->id); - pthread_mutex_unlock(&queue->rwmutex); - - if (workGroup == NULL) - break; - - if (cppadcg_pool_verbose) { - get_monotonic_time2(&workGroup->startTime); - } - - for (i = 0; i < workGroup->size; ++i) { - job = &workGroup->jobs[i]; - - if (cppadcg_pool_verbose) { - get_monotonic_time2(&job->startTime); - } - - int do_benchmark = job->elapsed != NULL; - if (do_benchmark) { - elapsed = -get_thread_time(&cputime, &info); - } - - /* Execute the job */ - func_buff = job->function; - arg_buff = job->arg; - func_buff(arg_buff); - - if (do_benchmark && info == 0) { - elapsed += get_thread_time(&cputime, &info); - if (info == 0) { - (*job->elapsed) = elapsed; - } - } - - if (cppadcg_pool_verbose) { - get_monotonic_time2(&job->endTime); - } - } - - if (cppadcg_pool_verbose) { - get_monotonic_time2(&workGroup->endTime); - - if (thread->processed_groups == NULL) { - thread->processed_groups = workGroup; - } else { - workGroup->prev = thread->processed_groups; - thread->processed_groups = workGroup; - } - } else { - free(workGroup->jobs); - free(workGroup); - } - } - - pthread_mutex_lock(&thpool->thcount_lock); - thpool->num_threads_working--; - if (!thpool->num_threads_working) { - pthread_cond_signal(&thpool->threads_all_idle); - } - pthread_mutex_unlock(&thpool->thcount_lock); - } - - pthread_mutex_lock(&thpool->thcount_lock); - thpool->num_threads_alive--; - pthread_mutex_unlock(&thpool->thcount_lock); - - return NULL; -} - - -/* Frees a thread */ -static void thread_destroy(Thread* thread) { - free(thread); -} - - -/* ============================ JOB QUEUE =========================== */ - - -/* Initialize queue */ -static int jobqueue_init(ThPool* thpool) { - - JobQueue* queue = (JobQueue*) malloc(sizeof(JobQueue)); - if (queue == NULL) { - return -1; - } - thpool->jobqueue = queue; - queue->len = 0; - queue->front = NULL; - queue->rear = NULL; - queue->group_front = NULL; - queue->total_time = 0; - queue->highest_expected_return = 0; - - queue->has_jobs = (BSem*) malloc(sizeof(BSem)); - if (queue->has_jobs == NULL) { - return -1; - } - - pthread_mutex_init(&(queue->rwmutex), NULL); - bsem_init(queue->has_jobs, 0); - - return 0; -} - - -/* Clear the queue */ -static void jobqueue_clear(ThPool* thpool) { - WorkGroup* group; - int size; - - do { - group = jobqueue_pull(thpool, -1); - if (group == NULL) { - size = 0; - } else { - size = group->size; - free(group->jobs); - free(group); - } - } while (size > 0); - - thpool->jobqueue->front = NULL; - thpool->jobqueue->rear = NULL; - bsem_reset(thpool->jobqueue->has_jobs); - thpool->jobqueue->len = 0; - thpool->jobqueue->group_front = NULL; - thpool->jobqueue->total_time = 0; - thpool->jobqueue->highest_expected_return = 0; -} - - -/** - * Add (allocated) job to queue without locks (internal function) - */ -static void jobqueue_push_internal(JobQueue* queue, - Job* newjob) { - newjob->prev = NULL; - - switch (queue->len) { - - case 0: /* if no jobs in queue */ - queue->front = newjob; - queue->rear = newjob; - break; - - default: /* if jobs in queue */ - queue->rear->prev = newjob; - queue->rear = newjob; - - } - if(newjob->avgElapsed != NULL) { - queue->total_time += *newjob->avgElapsed; - } - queue->len++; -} - -/** - * Add (allocated) job to queue - */ -static void jobqueue_push(JobQueue* queue, - Job* newjob) { - pthread_mutex_lock(&queue->rwmutex); - - jobqueue_push_internal(queue, newjob); - - bsem_post(queue->has_jobs); - - pthread_mutex_unlock(&queue->rwmutex); -} - - -/** - * Add (allocated) multiple jobs to queue - */ -static void jobqueue_multipush(JobQueue* queue, - Job* newjob[], - int nJobs) { - int i; - - pthread_mutex_lock(&queue->rwmutex); - - for(i = 0; i < nJobs; ++i) { - jobqueue_push_internal(queue, newjob[i]); - } - - bsem_post_all(queue->has_jobs); - - pthread_mutex_unlock(&queue->rwmutex); -} - -static Job* jobqueue_extract_single(JobQueue* queue) { - Job* job = queue->front; - - switch (queue->len) { - case 0: /* if no jobs in queue */ - return NULL; - - case 1: /* if one job in queue */ - queue->front = NULL; - queue->rear = NULL; - queue->len = 0; - queue->total_time = 0; - queue->highest_expected_return = 0; - return job; - - default: /* if >1 jobs in queue */ - queue->front = job->prev; - queue->len--; - if(job->avgElapsed != NULL) { - queue->total_time -= *job->avgElapsed; - } - return job; - } -} - -static void jobqueue_extract_single_group(JobQueue* queue, - WorkGroup* group) { - Job* job = jobqueue_extract_single(queue); - if(job != NULL) { - group->size = 1; - group->jobs = (Job*) malloc(sizeof(Job)); - group->jobs[0] = *job; // copy - free(job); - } else { - group->size = 0; - group->jobs = NULL; - } -} - -/** - * Get jobs from the queue(removes them from the queue) - * - * Notice: Caller MUST hold a mutex - */ -static WorkGroup* jobqueue_pull(ThPool* thpool, - int id) { - - WorkGroup* group; - Job* job; - float current_time; - float duration, duration_next, min_duration, target_duration; - struct timespec timeAux; - int info; - int i; - JobQueue* queue = thpool->jobqueue; - - if (schedule_strategy == SCHED_STATIC && queue->group_front != NULL) { - // STATIC - group = queue->group_front; - - queue->group_front = group->prev; - group->prev = NULL; - - } else if (queue->len == 0) { - // nothing to do - group = NULL; - - } else if (schedule_strategy == SCHED_DYNAMIC || queue->len == 1 || queue->total_time <= 0) { - // SCHED_DYNAMIC - group = (WorkGroup*) malloc(sizeof(WorkGroup)); - group->prev = NULL; - - if (cppadcg_pool_verbose) { - if (schedule_strategy == SCHED_GUIDED) { - if (queue->len == 1) - fprintf(stdout, "jobqueue_pull(): Thread %i given a work group with 1 job\n", id); - else if (queue->total_time <= 0) - fprintf(stdout, "jobqueue_pull(): Thread %i using single-job instead of multi-job (no timing information)\n", id); - } else if (schedule_strategy == SCHED_STATIC && queue->len >= 1) { - if (queue->total_time >= 0) { - // this should not happen but just in case the user messed up - fprintf(stderr, "jobqueue_pull(): Thread %i given a work group with 1 job\n", id); - } else { - fprintf(stdout, "jobqueue_pull(): Thread %i given a work group with 1 job\n", id); - } - } - } - - jobqueue_extract_single_group(thpool->jobqueue, group); - } else { // schedule_strategy == SCHED_GUIDED - // SCHED_GUIDED - group = (WorkGroup*) malloc(sizeof(WorkGroup)); - group->prev = NULL; - - job = queue->front; - - if (job->avgElapsed == NULL) { - if (cppadcg_pool_verbose) { - fprintf(stderr, "jobqueue_pull(): Thread %i using single job instead of multi-job (No timing information for current job)\n", id); - } - // cannot use this strategy (something went wrong!) - jobqueue_extract_single_group(thpool->jobqueue, group); - - } else { - // there are at least 2 jobs in the queue - group->size = 1; - duration = *job->avgElapsed; - duration_next = duration; - job = job->prev; - target_duration = queue->total_time * cppadcg_pool_guided_maxgroupwork / thpool->num_threads; // always positive - current_time = get_monotonic_time(&timeAux, &info); - - if (queue->highest_expected_return > 0 && info) { - min_duration = 0.9f * (queue->highest_expected_return - current_time); - if (target_duration < min_duration) { - target_duration = min_duration; - } - } - - do { - if (job->avgElapsed == NULL) { - break; - } - duration_next += *job->avgElapsed; - if (duration_next < target_duration) { - group->size++; - duration = duration_next; - } else { - break; - } - job = job->prev; - } while (job != queue->front); - - if (cppadcg_pool_verbose) { - fprintf(stdout, "jobqueue_pull(): Thread %i given a work group with %i jobs for %e s (target: %e s)\n", id, group->size, duration, target_duration); - } - - group->jobs = (Job*) malloc(group->size * sizeof(Job)); - for (i = 0; i < group->size; ++i) { - job = jobqueue_extract_single(thpool->jobqueue); - group->jobs[i] = *job; // copy - free(job); - } - - duration_next = current_time + duration; // the time when the current work is expected to end - if(duration_next > queue->highest_expected_return) - queue->highest_expected_return = duration_next; - } - - } - /* more than one job in queue -> post it */ - if (queue->len > 0 || queue->group_front != NULL) { - bsem_post(queue->has_jobs); - } - - return group; -} - - -/* Free all queue resources back to the system */ -static void jobqueue_destroy(ThPool* thpool) { - jobqueue_clear(thpool); - free(thpool->jobqueue->has_jobs); -} - - - - - -/* ======================== SYNCHRONISATION ========================= */ - - -/* Init semaphore to 1 or 0 */ -static void bsem_init(BSem* bsem, int value) { - if (value < 0 || value > 1) { - fprintf(stderr, "bsem_init(): Binary semaphore can take only values 1 or 0"); - exit(1); - } - pthread_mutex_init(&(bsem->mutex), NULL); - pthread_cond_init(&(bsem->cond), NULL); - bsem->v = value; -} - - -/* Reset semaphore to 0 */ -static void bsem_reset(BSem* bsem) { - bsem_init(bsem, 0); -} - - -/* Post to at least one thread */ -static void bsem_post(BSem* bsem) { - pthread_mutex_lock(&bsem->mutex); - bsem->v = 1; - pthread_cond_signal(&bsem->cond); - pthread_mutex_unlock(&bsem->mutex); -} - - -/* Post to all threads */ -static void bsem_post_all(BSem* bsem) { - pthread_mutex_lock(&bsem->mutex); - bsem->v = 1; - pthread_cond_broadcast(&bsem->cond); - pthread_mutex_unlock(&bsem->mutex); -} - - -/* Wait on semaphore until semaphore has value 0 */ -static void bsem_wait(BSem* bsem) { - pthread_mutex_lock(&bsem->mutex); - while (bsem->v != 1) { - pthread_cond_wait(&bsem->cond, &bsem->mutex); - } - bsem->v = 0; - pthread_mutex_unlock(&bsem->mutex); -} -)*=*"; - -const size_t CPPADCG_PTHREAD_POOL_C_FILE_SIZE = 43271; - diff --git a/ct_core/include/ct/external/cppad/cg/model/threadpool/pthread_pool_h.hpp b/ct_core/include/ct/external/cppad/cg/model/threadpool/pthread_pool_h.hpp deleted file mode 100644 index 333167f56..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/threadpool/pthread_pool_h.hpp +++ /dev/null @@ -1,102 +0,0 @@ -const char CPPADCG_PTHREAD_POOL_H_FILE[] = R"*=*(#ifndef CPPADCG_PTHREAD_POOL_H -#define CPPADCG_PTHREAD_POOL_H -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#ifdef __cplusplus -extern "C" { -#endif - -enum ScheduleStrategy {SCHED_STATIC = 1, - SCHED_DYNAMIC = 2, - SCHED_GUIDED = 3 - }; - -enum ElapsedTimeReference {ELAPSED_TIME_AVG, - ELAPSED_TIME_MIN}; - -typedef void (*cppadcg_thpool_function_type)(void*); - - -void cppadcg_thpool_set_threads(int n); - -int cppadcg_thpool_get_threads(); - - -void cppadcg_thpool_set_scheduler_strategy(enum ScheduleStrategy s); - -enum ScheduleStrategy cppadcg_thpool_get_scheduler_strategy(); - - -void cppadcg_thpool_set_guided_maxgroupwork(float v); - -float cppadcg_thpool_get_guided_maxgroupwork(); - - -unsigned int cppadcg_thpool_get_n_time_meas(); - -void cppadcg_thpool_set_n_time_meas(unsigned int n); - - -enum ElapsedTimeReference cppadcg_thpool_get_time_meas_ref(); - -void cppadcg_thpool_set_time_meas_ref(enum ElapsedTimeReference r); - - -void cppadcg_thpool_set_verbose(int v); - -int cppadcg_thpool_is_verbose(); - - -void cppadcg_thpool_set_disabled(int disabled); - -int cppadcg_thpool_is_disabled(); - - -void cppadcg_thpool_prepare(); - -void cppadcg_thpool_add_job(cppadcg_thpool_function_type function, - void* arg, - const float* avgElapsed, - float* elapsed); - -void cppadcg_thpool_add_jobs(cppadcg_thpool_function_type functions[], - void* args[], - const float refElapsed[], - float elapsed[], - const int order[], - int job2Thread[], - int nJobs, - int lastElapsedChanged); - -void cppadcg_thpool_wait(); - -void cppadcg_thpool_update_order(float refElapsed[], - unsigned int nTimeMeas, - const float elapsed[], - int order[], - int nJobs); - -void cppadcg_thpool_shutdown(); - -#ifdef __cplusplus -} -#endif - -#endif -)*=*"; - -const size_t CPPADCG_PTHREAD_POOL_H_FILE_SIZE = 2730; - diff --git a/ct_core/include/ct/external/cppad/cg/model/threadpool/thread_pool_schedule_strategy.hpp b/ct_core/include/ct/external/cppad/cg/model/threadpool/thread_pool_schedule_strategy.hpp deleted file mode 100644 index 66257cdd5..000000000 --- a/ct_core/include/ct/external/cppad/cg/model/threadpool/thread_pool_schedule_strategy.hpp +++ /dev/null @@ -1,30 +0,0 @@ -#ifndef CPPAD_CG_THREAD_POOL_SCHEDULE_STRATEGY_INCLUDED -#define CPPAD_CG_THREAD_POOL_SCHEDULE_STRATEGY_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -enum class ThreadPoolScheduleStrategy { - STATIC = 1, // all jobs are assigned to a thread at the beginning - DYNAMIC = 2, // each thread only executes a single job at a time - GUIDED = 3 // each thread can execute multiple jobs before returning to the pool -}; - -} -} - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/nan.hpp b/ct_core/include/ct/external/cppad/cg/nan.hpp deleted file mode 100644 index 600d3209a..000000000 --- a/ct_core/include/ct/external/cppad/cg/nan.hpp +++ /dev/null @@ -1,35 +0,0 @@ -#ifndef CPPAD_CG_NAN_HPP -#define CPPAD_CG_NAN_HPP -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { - -template -inline bool isnan(const cg::CG &s) { - using namespace CppAD::cg; - - if (s.isVariable()) { - return false; - } else { - // a parameter - const Base& v = s.getValue(); - return (v != v); - } -} - -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/nodes/index_assign_operation_node.hpp b/ct_core/include/ct/external/cppad/cg/nodes/index_assign_operation_node.hpp deleted file mode 100644 index 6a3d2fb59..000000000 --- a/ct_core/include/ct/external/cppad/cg/nodes/index_assign_operation_node.hpp +++ /dev/null @@ -1,120 +0,0 @@ -#ifndef CPPAD_CG_INDEX_ASSIGN_OPERATION_NODE_INCLUDED -#define CPPAD_CG_INDEX_ASSIGN_OPERATION_NODE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * An index reference operation node. - * - * This is a custom OperationNode class and therefore cannot be transformed - * into any other node type (makeAlias() and setOperation() might not work). - * - * @author Joao Leal - */ -template -class IndexAssignOperationNode : public OperationNode { - friend class CodeHandler; -private: - IndexPattern& indexPattern_; -public: - - inline OperationNode& getIndex() const { - const std::vector >& args = this->getArguments(); - CPPADCG_ASSERT_KNOWN(!args.empty(), "Invalid number of arguments"); - - OperationNode* aNode = args[0].getOperation(); - CPPADCG_ASSERT_KNOWN(aNode != nullptr && aNode->getOperationType() == CGOpCode::IndexDeclaration, "Invalid argument operation type"); - - return static_cast&> (*aNode); - } - - inline const IndexPattern& getIndexPattern() const { - return indexPattern_; - } - - inline IndexPattern& getIndexPattern() { - return indexPattern_; - } - - inline std::vector*> getIndexPatternIndexes() const { - std::vector*> iargs; - - const std::vector >& args = this->getArguments(); - - CPPADCG_ASSERT_KNOWN(args[1].getOperation() != nullptr && - args[1].getOperation()->getOperationType() == CGOpCode::Index, "Invalid argument operation type"); - iargs.push_back(&static_cast*> (args[1].getOperation())->getIndex()); - - if (args.size() > 2) { - CPPADCG_ASSERT_KNOWN(args[2].getOperation() != nullptr && - args[2].getOperation()->getOperationType() == CGOpCode::Index, "Invalid argument operation type"); - iargs.push_back(&static_cast*> (args[2].getOperation())->getIndex()); - } - - return iargs; - } - - inline virtual ~IndexAssignOperationNode() { - } - -protected: - - /** - * @param handler owner of this node - * @param index the index that is being assigned - * @param indexPattern the index expression used to define the index value - * @param index1 - */ - inline IndexAssignOperationNode(CodeHandler* handler, - OperationNode& index, - IndexPattern& indexPattern, - IndexOperationNode& index1) : - OperationNode(handler, CGOpCode::IndexAssign,{index, index1}), - indexPattern_(indexPattern) { - } - - inline IndexAssignOperationNode(CodeHandler* handler, - OperationNode& index, - IndexPattern& indexPattern, - IndexOperationNode* index1, - IndexOperationNode* index2) : - OperationNode(handler, CGOpCode::IndexAssign, std::vector (0), createArguments(index, index1, index2)), - indexPattern_(indexPattern) { - } - - inline static std::vector > createArguments(OperationNode& index, - IndexOperationNode* index1, - IndexOperationNode* index2) { - std::vector > args(1 + (index1 != nullptr)+ (index2 != nullptr)); - - args[0] = index; - if (index1 != nullptr) - args[1] = *index1; - if (index2 != nullptr) { - args.back() = *index2; - } - - return args; - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/nodes/index_operation_node.hpp b/ct_core/include/ct/external/cppad/cg/nodes/index_operation_node.hpp deleted file mode 100644 index a12307884..000000000 --- a/ct_core/include/ct/external/cppad/cg/nodes/index_operation_node.hpp +++ /dev/null @@ -1,88 +0,0 @@ -#ifndef CPPAD_CG_INDEX_OPERATION_NODE_INCLUDED -#define CPPAD_CG_INDEX_OPERATION_NODE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * An index reference operation node - * - * This is a custom OperationNode class and therefore cannot be transformed - * into any other node type (makeAlias() and setOperation() might not work). - * - * @author Joao Leal - */ -template -class IndexOperationNode : public OperationNode { - friend class CodeHandler; -public: - - inline bool isDefinedLocally() const { - return this->getArguments().size() > 1; - } - - inline OperationNode& getIndexCreationNode() const { - const std::vector >& args = this->getArguments(); - CPPADCG_ASSERT_KNOWN(!args.empty(), "Invalid number of arguments"); - CPPADCG_ASSERT_KNOWN(args.back().getOperation() != nullptr, "Invalid argument type"); - return *args.back().getOperation(); - } - - inline const OperationNode& getIndex() const { - const std::vector >& args = this->getArguments(); - CPPADCG_ASSERT_KNOWN(!args.empty(), "Invalid number of arguments"); - - OperationNode* aNode = args[0].getOperation(); - CPPADCG_ASSERT_KNOWN(aNode != nullptr && aNode->getOperationType() == CGOpCode::IndexDeclaration, "Invalid argument operation type"); - - return static_cast&> (*aNode); - } - - inline void makeAssigmentDependent(IndexAssignOperationNode& indexAssign) { - std::vector >& args = this->getArguments(); - - args.resize(2); - args[0] = indexAssign.getIndex(); - args[1] = indexAssign; - } - - inline virtual ~IndexOperationNode() { - } - -protected: - - inline IndexOperationNode(CodeHandler* handler, - OperationNode& indexDcl) : - OperationNode(handler, CGOpCode::Index, indexDcl) { - } - - inline IndexOperationNode(CodeHandler* handler, - LoopStartOperationNode& loopStart) : - OperationNode(handler, CGOpCode::Index,{loopStart.getIndex(), loopStart}) { - } - - inline IndexOperationNode(CodeHandler* handler, - IndexAssignOperationNode& indexAssign) : - OperationNode(handler, CGOpCode::Index,{indexAssign.getIndex(), indexAssign}) { - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/nodes/loop_end_operation_node.hpp b/ct_core/include/ct/external/cppad/cg/nodes/loop_end_operation_node.hpp deleted file mode 100644 index 4f2dae363..000000000 --- a/ct_core/include/ct/external/cppad/cg/nodes/loop_end_operation_node.hpp +++ /dev/null @@ -1,70 +0,0 @@ -#ifndef CPPAD_CG_LOOP_END_OPERATION_NODE_INCLUDED -#define CPPAD_CG_LOOP_END_OPERATION_NODE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * An operation node that marks the end of a loop. - * - * This is a custom OperationNode class and therefore cannot be transformed - * into any other node type (makeAlias() and setOperation() might not work). - * - * @author Joao Leal - */ -template -class LoopEndOperationNode : public OperationNode { - friend class CodeHandler; -public: - - inline const LoopStartOperationNode& getLoopStart() const { - const std::vector >& args = this->getArguments(); - CPPADCG_ASSERT_KNOWN(args.size() > 0, "There must be at least one argument"); - - OperationNode* aNode = args[0].getOperation(); - CPPADCG_ASSERT_KNOWN(aNode != nullptr && aNode->getOperationType() == CGOpCode::LoopStart, "The first argument must be the loop start operation"); - - return dynamic_cast&> (*aNode); - } - - inline virtual ~LoopEndOperationNode() { - } - -protected: - - inline LoopEndOperationNode(CodeHandler* handler, - LoopStartOperationNode& loopStart, - const std::vector >& endArgs) : - OperationNode(handler, CGOpCode::LoopEnd, std::vector(0), createArguments(loopStart, endArgs)) { - } - -private: - - static inline std::vector > createArguments(LoopStartOperationNode& lstart, - const std::vector >& endArgs) { - std::vector > args(1 + endArgs.size()); - args[0] = lstart; - std::copy(endArgs.begin(), endArgs.end(), args.begin() + 1); - return args; - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/nodes/loop_start_operation_node.hpp b/ct_core/include/ct/external/cppad/cg/nodes/loop_start_operation_node.hpp deleted file mode 100644 index 5a3bff3d9..000000000 --- a/ct_core/include/ct/external/cppad/cg/nodes/loop_start_operation_node.hpp +++ /dev/null @@ -1,87 +0,0 @@ -#ifndef CPPAD_CG_LOOP_START_OPERATION_NODE_INCLUDED -#define CPPAD_CG_LOOP_START_OPERATION_NODE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * An operation node that marks the beginning of a loop. - * - * This is a custom OperationNode class and therefore cannot be transformed - * into any other node type (makeAlias() and setOperation() might not work). - * - * @author Joao Leal - */ -template -class LoopStartOperationNode : public OperationNode { - friend class CodeHandler; -public: - - inline OperationNode& getIndex() const { - const std::vector >& args = this->getArguments(); - CPPADCG_ASSERT_KNOWN(!args.empty(), "Invalid number of arguments"); - - OperationNode* aNode = args[0].getOperation(); - CPPADCG_ASSERT_KNOWN(aNode != nullptr && aNode->getOperationType() == CGOpCode::IndexDeclaration, "Invalid argument operation type"); - - return static_cast&> (*aNode); - } - - inline IndexOperationNode* getIterationCountNode() const { - if (this->getInfo().empty()) { - CPPADCG_ASSERT_KNOWN(this->getArguments().size() > 1, "Invalid number of arguments."); - - OperationNode* aNode = this->getArguments()[1].getOperation(); - CPPADCG_ASSERT_KNOWN(aNode != nullptr && aNode->getOperationType() == CGOpCode::Index, "Invalid argument node type"); - - return static_cast*> (aNode); - } - - return nullptr; - } - - inline const size_t getIterationCount() const { - if (this->getInfo().empty()) { - return 0; - } - return this->getInfo()[0]; - } - - inline virtual ~LoopStartOperationNode() { - } - -protected: - - inline LoopStartOperationNode(CodeHandler* handler, - OperationNode& indexDcl, - size_t iterationCount) : - OperationNode(handler, CGOpCode::LoopStart, indexDcl) { - this->getInfo().push_back(iterationCount); - } - - inline LoopStartOperationNode(CodeHandler* handler, - OperationNode& indexDcl, - IndexOperationNode& iterCount) : - OperationNode(handler, CGOpCode::LoopStart,{indexDcl, iterCount}) { - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/nodes/print_operation_node.hpp b/ct_core/include/ct/external/cppad/cg/nodes/print_operation_node.hpp deleted file mode 100644 index fb7bf2c55..000000000 --- a/ct_core/include/ct/external/cppad/cg/nodes/print_operation_node.hpp +++ /dev/null @@ -1,72 +0,0 @@ -#ifndef CPPAD_CG_PRINT_OPERATION_NODE_INCLUDED -#define CPPAD_CG_PRINT_OPERATION_NODE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * An operation node which prints out a variable value or parameter. - * - * This is a custom OperationNode class and therefore cannot be transformed - * into any other node type (makeAlias() and setOperation() might not work). - * - * @author Joao Leal - */ -template -class PrintOperationNode : public OperationNode { - friend class CodeHandler; -protected: - std::string before_; - std::string after_; -public: - - inline const std::string& getBeforeString() const { - return before_; - } - - inline void setBeforeString(const std::string& before) { - before_ = before; - } - - inline const std::string& getAfterString() const { - return after_; - } - - inline void setAfterString(const std::string& after) { - after_ = after; - } - - inline virtual ~PrintOperationNode() { - } - -protected: - - inline PrintOperationNode(CodeHandler* handler, - const std::string& before, - const Argument& arg, - const std::string& after) : - OperationNode(handler, CGOpCode::Pri, arg), - before_(before), - after_(after) { - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/operation.hpp b/ct_core/include/ct/external/cppad/cg/operation.hpp deleted file mode 100644 index 89ba0b1bd..000000000 --- a/ct_core/include/ct/external/cppad/cg/operation.hpp +++ /dev/null @@ -1,168 +0,0 @@ -#ifndef CPPAD_CG_OPERATION_INCLUDED -#define CPPAD_CG_OPERATION_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Operation types for OperationNode - * - * @author Joao Leal - */ -enum class CGOpCode { - Assign, // a = b - Abs, // abs(variable) - Acos, // acos(variable) - Acosh, // acosh(variable) - Add, // a + b - Alias, // alias (reference to another operation) - ArrayCreation, // dense array {a, b, c ...} - SparseArrayCreation, // {a, b, c ...}; {index1, index2, index3, ...}; - ArrayElement, // x[i] - Asin, // asin(variable) - Asinh, // asinh(variable) - Atan, // atan(variable) - Atanh, // atanh(variable) - AtomicForward, // atomicFunction.forward(q, p, vx, vy, tx, ty) - AtomicReverse, // atomicFunction.reverse(p, tx, ty, px, py) - ComLt, // result = left < right? trueCase: falseCase - ComLe, // result = left <= right? trueCase: falseCase - ComEq, // result = left == right? trueCase: falseCase - ComGe, // result = left >= right? trueCase: falseCase - ComGt, // result = left > right? trueCase: falseCase - ComNe, // result = left != right? trueCase: falseCase - Cosh, // cosh(variable) - Cos, // cos(variable) - Div, // a / b - Erf, // erf(variable) - Exp, // exp(variable) - Expm1, // expm1(variable) - Inv, // independent variable - Log, // log(variable) - Log1p, // log1p(variable) - Mul, // a * b - Pow, // pow(a, b) - Pri, // PrintFor(text, parameter or variable, parameter or variable) - Sign, // result = (x > 0)? 1.0:((x == 0)? 0.0:-1) - Sinh, // sinh(variable) - Sin, // sin(variable) - Sqrt, // sqrt(variable) - Sub, // a - b - Tanh, // tanh(variable) - Tan, // tan(variable) - UnMinus, // -(a) - DependentMultiAssign, // operation which associates a dependent variables with loops and regular operations - DependentRefRhs, // operation referencing a dependent variable (right hand side only) - IndexDeclaration, // an integer index declaration - Index, // an integer index - IndexAssign, // assignment of an integer index to an index pattern expression - LoopStart, // for() {} - LoopIndexedIndep, // indexed independent used by a loop - LoopIndexedDep, // indexed output for a dependent variable from a loop - LoopIndexedTmp, // indexed output for a temporary variable from a loop - LoopEnd, // endfor - TmpDcl, // marks the beginning of the use of a temporary variable across several scopes (used by LoopIndexedTmp) - Tmp, // reference to a temporary variable defined by TmpDcl - IndexCondExpr, // a condition expression which returns a boolean - StartIf, // the start of an if statement - ElseIf, // else if() - Else, // else - EndIf, // end of if - CondResult, // assignment inside an if branch - UserCustom, // a custom type added by a user which has no direct support in CppADCodeGen - NumberOp // total number of operation types -}; - -inline std::ostream& operator<<(std::ostream& os, const CGOpCode& op) { - static const char* OpNameTable[] = { - "$1 = $2", // Assign - "abs($1)", // Abs - "acos($1)", // Acos - "acosh($1)", // Acosh - "$1 + $2", // Add - "alias($1)", // Alias - "new array[size]", // ArrayCreation - "new sparseArray[size]", // SparseArrayCreation - "array[i]", // ArrayElement - "asin($1)", // Asin - "asinh($1)", // Asinh - "atan($1)", // Atan - "atanh($1)", // Atanh - "atomicFunction.forward(q, p, vx, vy, tx, ty)", // AtomicForward - "atomicFunction.reverse(p, tx, ty, px, py)", // AtomicReverse - "result = ($1 < $2)? $3 : $4", // ComLt - "result = ($1 <= $2)? $3 : $4", // ComLe - "result = ($1 == $2)? $3 : $4", // ComEq - "result = ($1 >= $2)? $3 : $4", // ComGe - "result = ($1 > $2)? $3 : $4", // ComGt - "result = ($1 != $2)? $3 : $4", // ComNe - "cosh($1)", // Cosh - "cos($1)", // Cos - "$1 / $2", // Div - "erf($1)", // Erf - "exp($1)", // Exp - "expm1($1)", // Expm1 - "independent()", // Inv - "log($1)", // Log - "log1p($1)", // Log1p - "$1 * $2", // Mul - "pow($1, $2)", // Pow - "print($1)", // Pri - "sign($1)", // Sign - "sinh($1)", // Sinh - "sin($1)", // Sin - "sqrt($1)", // Sqrt - "$1 - $2", // Sub - "tanh($1)", // Tanh - "tan($1)", // Tan - "-($1)", // UnMinus - "dep($1) = ($2) + ...", // DependentMultiAssign - "depref($1)", // DependentRefRhs - "index declaration", // IndexDeclaration - "index", // Index - "index = expression()", // IndexAssign - "for", // LoopStart - "loopIndexedIndep", // LoopIndexedIndep - "loopIndexedDep", // LoopIndexedDep - "loopIndexedTmp", // LoopIndexedTmp - "endfor", // LoopEnd - "declare tempVar", // TmpDcl - "tempVar", // Tmp - "bool(index expression)", // IndexCondExpr - "if()", // StartIf - "else if()", // ElseIf - "else", // Else - "endif", // EndIf - "ifResult =", // CondResult - "custom", // UserCustom - "numberOp" - }; - // check ensuring conversion to size_t is as expected - CPPADCG_ASSERT_UNKNOWN(size_t(CGOpCode::NumberOp) + 1 == sizeof(OpNameTable)/sizeof(OpNameTable[0])); - - // this test ensures that all indices are within the table - CPPADCG_ASSERT_UNKNOWN(int(op) >= 0 && size_t(op) < size_t(CGOpCode::NumberOp)); - - os << OpNameTable[size_t(op)]; - - return os; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/operation_node.hpp b/ct_core/include/ct/external/cppad/cg/operation_node.hpp deleted file mode 100644 index 81075572c..000000000 --- a/ct_core/include/ct/external/cppad/cg/operation_node.hpp +++ /dev/null @@ -1,374 +0,0 @@ -#ifndef CPPAD_CG_EXPRESSION_NODE_INCLUDED -#define CPPAD_CG_EXPRESSION_NODE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * An operation node. - * - * @author Joao Leal - */ -template -class OperationNode { - friend class CodeHandler; -public: - typedef typename std::vector >::iterator iterator; - typedef typename std::vector >::const_iterator const_iterator; - typedef typename std::vector >::const_reverse_iterator const_reverse_iterator; - typedef typename std::vector >::reverse_iterator reverse_iterator; -public: - static const std::set CUSTOM_NODE_CLASS; -private: - /** - * the source code handler that own this node - * (only null for temporary OperationNodes) - */ - CodeHandler* handler_; - /** - * the operation type represented by this node - */ - CGOpCode operation_; - /** - * additional information/options associated with the operation type - */ - std::vector info_; - /** - * arguments required by the operation - * (empty for independent variables and possibly for the 1st assignment - * of a dependent variable) - */ - std::vector > arguments_; - /** - * index in the CodeHandler managed nodes array - */ - size_t pos_; - /** - * name for the result of this operation - */ - std::string* name_; -public: - /** - * Changes the current operation type into an Alias. - * @param other the operation node or value this node is going to reference - */ - inline void makeAlias(const Argument& other) { - CPPADCG_ASSERT_UNKNOWN(CUSTOM_NODE_CLASS.find(operation_) == CUSTOM_NODE_CLASS.end()); // TODO: consider relaxing this check - - operation_ = CGOpCode::Alias; - arguments_.resize(1); - arguments_[0] = other; - delete name_; - name_ = nullptr; - } - - /** - * Provides the source code handler that owns this node. - * It can only be null for temporary nodes. - * - * @return a CodeHandler which owns this nodes memory (possibly null) - */ - inline CodeHandler* getCodeHandler() const { - return handler_; - } - - /** - * Provides the operation type represented by this node. - * @return Mathematical operation type which this node is the result of. - */ - inline CGOpCode getOperationType() const { - return operation_; - } - - /** - * Changes the current operation type. - * The previous operation information/options might also have to be - * changed, use getInfo() to change it if required. - * @param op the new operation type - * @param arguments the arguments for the new operation - */ - inline void setOperation(CGOpCode op, - const std::vector >& arguments = std::vector >()) { - CPPADCG_ASSERT_UNKNOWN(op == operation_ || CUSTOM_NODE_CLASS.find(op) == CUSTOM_NODE_CLASS.end()); // cannot transform into a node with a custom class - - operation_ = op; - arguments_ = arguments; - } - - /** - * Provides the arguments used in the operation represented by this - * node. - * @return the arguments for the operation in this node (read-only) - */ - inline const std::vector >& getArguments() const { - return arguments_; - } - - /** - * Provides the arguments used in the operation represented by this - * node. - * @return the arguments for the operation in this node - */ - inline std::vector >& getArguments() { - return arguments_; - } - - /** - * Provides additional information used in the operation. - * @return the additional operation information/options (read-only) - */ - inline const std::vector& getInfo() const { - return info_; - } - - /** - * Provides additional information used in the operation. - * @return the additional operation information/options - */ - inline std::vector& getInfo() { - return info_; - } - - /** - * Provide the variable name assigned to this node. - * @return a variable name for the result of this operation or null if - * no name was assigned to this node yet - */ - inline const std::string* getName() const { - return name_; - } - - /** - * Defines a new variable name for this node - * @param name a variable name - */ - inline void setName(const std::string& name) { - if (name_ != nullptr) - *name_ = name; - else - name_ = new std::string(name); - } - - /** - * Clears any name assigned to this node. - */ - inline void clearName() { - delete name_; - name_ = nullptr; - } - - /** - * Provides the index in CodeHandler which owns this OperationNode. - * A value of std::numeric_limits::max() means that it is not - * managed by any CodeHandler. - * This value can change if its position changes in the CodeHandler. - * - * @return the index in the CodeHandler's array of managed nodes - */ - inline size_t getHandlerPosition() const { - return pos_; - } - - // argument iterators - - inline iterator begin() { - return arguments_.begin(); - } - - inline const_iterator begin() const { - return arguments_.begin(); - } - - inline iterator end() { - return arguments_.end(); - } - - inline const_iterator end() const { - return arguments_.end(); - } - - inline reverse_iterator rbegin() { - return arguments_.rbegin(); - } - - inline const_reverse_iterator rbegin() const { - return arguments_.rbegin(); - } - - inline reverse_iterator rend() { - return arguments_.rend(); - } - - inline const_reverse_iterator rend() const { - return arguments_.rend(); - } - - inline const_iterator cbegin() const noexcept { - return arguments_.cbegin(); - } - - inline const_iterator cend() const noexcept { - return arguments_.cend(); - } - - inline const_reverse_iterator crbegin() const noexcept { - return arguments_.crbegin(); - } - - inline const_reverse_iterator crend() const noexcept { - return arguments_.crend(); - } - - inline virtual ~OperationNode() { - delete name_; - } - -protected: - - inline OperationNode(const OperationNode& orig) : - handler_(orig.handler_), - operation_(orig.operation_), - info_(orig.info_), - arguments_(orig.arguments_), - pos_(std::numeric_limits::max()), - name_(orig.name_ != nullptr ? new std::string(*orig.name_) : nullptr) { - } - - inline OperationNode(CodeHandler* handler, - CGOpCode op) : - handler_(handler), - operation_(op), - pos_(std::numeric_limits::max()), - name_(nullptr) { - } - - inline OperationNode(CodeHandler* handler, - CGOpCode op, - const Argument& arg) : - handler_(handler), - operation_(op), - arguments_ {arg}, - pos_(std::numeric_limits::max()), - name_(nullptr) { - } - - inline OperationNode(CodeHandler* handler, - CGOpCode op, - std::vector >&& args) : - handler_(handler), - operation_(op), - arguments_(std::move(args)), - pos_(std::numeric_limits::max()), - name_(nullptr) { - } - - inline OperationNode(CodeHandler* handler, - CGOpCode op, - std::vector&& info, - std::vector >&& args) : - handler_(handler), - operation_(op), - info_(std::move(info)), - arguments_(std::move(args)), - pos_(std::numeric_limits::max()), - name_(nullptr) { - } - - inline OperationNode(CodeHandler* handler, - CGOpCode op, - const std::vector& info, - const std::vector >& args) : - handler_(handler), - operation_(op), - info_(info), - arguments_(args), - pos_(std::numeric_limits::max()), - name_(nullptr) { - } - - inline void setHandlerPosition(size_t pos) { - pos_ = pos; - } - -public: - - /** - * Creates a temporary operation node. - * - * @warning This node should never be provided to a CodeHandler. - */ - static std::unique_ptr> makeTemporaryNode(CGOpCode op, - const std::vector& info, - const std::vector >& args) { - return std::unique_ptr> (new OperationNode(nullptr, op, info, args)); - } - -protected: - static inline std::set makeCustomNodeClassesSet(); - -}; - -template -inline std::set OperationNode::makeCustomNodeClassesSet() { - std::set s; - s.insert(CGOpCode::IndexAssign); - s.insert(CGOpCode::Index); - s.insert(CGOpCode::LoopStart); - s.insert(CGOpCode::LoopEnd); - s.insert(CGOpCode::Pri); - return s; -} - -template -const std::set OperationNode::CUSTOM_NODE_CLASS = makeCustomNodeClassesSet(); - -template -inline std::ostream& operator<<( - std::ostream& os, //< stream to write to - const OperationNode& c) { - CGOpCode op = c.getOperationType(); - switch (op) { - case CGOpCode::ArrayCreation: - os << "new $1[" << c.getArguments().size() << "]"; - break; - case CGOpCode::SparseArrayCreation: - os << "new $1[" << c.getInfo()[0] << "]"; - break; - case CGOpCode::ArrayElement: - os << "$1[" << c.getInfo()[0] << "]"; - break; - case CGOpCode::AtomicForward: - os << "atomicFunction.forward(" << c.getInfo()[0] << ", " << c.getInfo()[1] << ", vx, vy, $1, $2)"; - break; - case CGOpCode::AtomicReverse: - os << "atomicFunction.reverse(" << c.getInfo()[0] << ", $1, $2, $3, $4)"; - break; - case CGOpCode::Sign: - os << "if($1 > 0) { 1 } else if($1 == 0) { 0 } else { -1 }"; - break; - - default: - os << op; - } - - return os; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/operation_node_name_streambuf.hpp b/ct_core/include/ct/external/cppad/cg/operation_node_name_streambuf.hpp deleted file mode 100644 index 988b4ea51..000000000 --- a/ct_core/include/ct/external/cppad/cg/operation_node_name_streambuf.hpp +++ /dev/null @@ -1,87 +0,0 @@ -#ifndef CPPAD_CG_OPERATION_NODE_NAME_STREAMBUF_INCLUDED -#define CPPAD_CG_OPERATION_NODE_NAME_STREAMBUF_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * A stream buffer used to recover OperationNode names defined using - * CppAD::PrintFor. - * - * @note There can only be one at a time. - * @note It must be used in the same thread it was created in! - * - * @author Joao Leal - */ -template -class OperationNodeNameStreambuf : public std::streambuf { -private: - typedef typename std::streambuf::char_type char_type; - typedef typename std::streambuf::int_type int_type; - typedef typename std::streambuf::pos_type pos_type; -private: - thread_local static OperationNodeNameStreambuf* BUF; -private: - OperationNode * node_; -public: - OperationNodeNameStreambuf() : - node_(nullptr) { - if (BUF != nullptr) { - throw CGException("Only one OperationNodeNameStreambuf can exist at a time in each thread"); - } - if (CGOStreamFunc::FUNC != nullptr) { - throw CGException("CGOStreamFunc::FUNC already defined in this thread"); - } - BUF = this; - CGOStreamFunc::FUNC = registerNode; - } - - virtual ~OperationNodeNameStreambuf() { - BUF = nullptr; - CGOStreamFunc::FUNC = nullptr; - } - - virtual std::streamsize xsputn(const char_type* s, - std::streamsize n) override { - if (node_ != nullptr && n > 0) { - node_->setName(std::string(s, n)); - node_ = nullptr; - } - return n; - } - - //virtual int_type overflow(int_type c) override { - // return traits_type::eof(); - //} - -private: - static std::ostream& registerNode(std::ostream& os, - const CG& c) { - if(c.isVariable()) { - BUF->node_ = c.getOperationNode(); - } - return os; - } -}; - -template -thread_local OperationNodeNameStreambuf* OperationNodeNameStreambuf::BUF = nullptr; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/operation_path.hpp b/ct_core/include/ct/external/cppad/cg/operation_path.hpp deleted file mode 100644 index 9549eb7e7..000000000 --- a/ct_core/include/ct/external/cppad/cg/operation_path.hpp +++ /dev/null @@ -1,211 +0,0 @@ -#ifndef CPPAD_CG_OPERATION_PATH_INCLUDED -#define CPPAD_CG_OPERATION_PATH_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include -#include - -namespace CppAD { -namespace cg { - -/** - * Finds all paths from a root node to a target node. - * - * @param foundGraph stores the graph connecting root to target - * @param root the current node - * @param target the node to be found - * @param bifurcations the current number of bifurcations in the graph - * @param maxBifurcations the maximum number of bifurcations allowed - * (this function will return if this value was reached) - */ -template -inline bool findPathGraph(BidirGraph& foundGraph, - OperationNode& root, - OperationNode& target, - size_t& bifurcations, - size_t maxBifurcations = std::numeric_limits::max()) { - if (bifurcations >= maxBifurcations) { - return false; - } - - if (&root == &target) { - return true; - } - - if(foundGraph.contains(root)) { - return true; // been here and it was saved in foundGraph - } - - auto* h = root.getCodeHandler(); - - if(h->isVisited(root)) { - return false; // been here but it was not saved in foundGraph - } - - // not visited yet - h->markVisited(root); // mark node as visited - - PathNodeEdges& info = foundGraph[root]; - - const auto& args = root.getArguments(); - - bool found = false; - for(size_t i = 0; i < args.size(); ++i) { - const Argument& a = args[i]; - if(a.getOperation() != nullptr ) { - auto& aNode = *a.getOperation(); - if(findPathGraph(foundGraph, aNode, target, bifurcations, maxBifurcations)) { - foundGraph.connect(info, root, i); - if(found) { - bifurcations++; // multiple ways to get to target - } else { - found = true; - } - } - } - } - - if(!found) { - foundGraph.erase(root); - } - - return found; -} - -template -inline BidirGraph CodeHandler::findPathGraph(OperationNode& root, - OperationNode& target) { - size_t bifurcations = 0; - return findPathGraph(root, target, bifurcations); -} - -template -inline BidirGraph CodeHandler::findPathGraph(OperationNode& root, - OperationNode& target, - size_t& bifurcations, - size_t maxBifurcations) { - startNewOperationTreeVisit(); - - BidirGraph foundGraph; - - if (bifurcations <= maxBifurcations) { - if (&root == &target) { - foundGraph[root]; - } else { - CppAD::cg::findPathGraph(foundGraph, root, target, bifurcations, maxBifurcations); - } - } - - return foundGraph; -} - - -template -inline std::vector > > CodeHandler::findPaths(OperationNode& root, - OperationNode& code, - size_t max) { - std::vector > > found; - - startNewOperationTreeVisit(); - - if (max > 0) { - std::vector > path2node; - path2node.reserve(30); - path2node.push_back(OperationPathNode (&root, 0)); - - if (&root == &code) { - found.push_back(path2node); - } else { - findPaths(path2node, code, found, max); - } - } - - return found; -} - -template -inline void CodeHandler::findPaths(SourceCodePath& currPath, - OperationNode& code, - std::vector& found, - size_t max) { - - OperationNode* currNode = currPath.back().node; - if (&code == currNode) { - found.push_back(currPath); - return; - } - - const std::vector >& args = currNode->getArguments(); - if (args.empty()) - return; // nothing to look in - - if (isVisited(*currNode)) { - // already searched inside this node - // any match would have been saved in found - std::vector pathsFromNode = findPathsFromNode(found, *currNode); - for (const SourceCodePath& pathFromNode : pathsFromNode) { - SourceCodePath newPath(currPath.size() + pathFromNode.size()); - std::copy(currPath.begin(), currPath.end(), newPath.begin()); - std::copy(pathFromNode.begin(), pathFromNode.end(), newPath.begin() + currPath.size()); - found.push_back(newPath); - } - - } else { - // not visited yet - markVisited(*currNode); // mark node as visited - - size_t size = args.size(); - for (size_t i = 0; i < size; ++i) { - OperationNode* a = args[i].getOperation(); - if (a != nullptr) { - currPath.push_back(OperationPathNode (a, i)); - findPaths(currPath, code, found, max); - currPath.pop_back(); - if (found.size() == max) { - return; - } - } - } - } -} - -template -inline std::vector > > CodeHandler::findPathsFromNode(const std::vector nodePaths, - OperationNode& node) { - - std::vector foundPaths; - std::set argsFound; - - for (const SourceCodePath& path : nodePaths) { - size_t size = path.size(); - for (size_t i = 0; i < size - 1; i++) { - const OperationPathNode& pnode = path[i]; - if (pnode.node == &node) { - if (argsFound.find(path[i + 1].argIndex) == argsFound.end()) { - foundPaths.push_back(SourceCodePath(path.begin() + i + 1, path.end())); - argsFound.insert(path[i + 1].argIndex); - } - } - } - } - - return foundPaths; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/operation_path_node.hpp b/ct_core/include/ct/external/cppad/cg/operation_path_node.hpp deleted file mode 100644 index 287c5ddf3..000000000 --- a/ct_core/include/ct/external/cppad/cg/operation_path_node.hpp +++ /dev/null @@ -1,64 +0,0 @@ -#ifndef CPPAD_CG_OPERATION_PATH_NODE_INCLUDED -#define CPPAD_CG_OPERATION_PATH_NODE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2016 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -struct OperationPathNode { - /** - * an operation - */ - OperationNode* node; - /** - * argument index for the next node in the path - */ - size_t argIndex; - - inline OperationPathNode() : - node(nullptr), - argIndex(0) { - } - - inline OperationPathNode(OperationNode* node, - size_t argIndex) : - node(node), - argIndex(argIndex) { - } - - inline bool operator<(const OperationPathNode& right) const { - return node < right.node || argIndex < right.argIndex; - } - -}; - -template -inline bool operator==(const OperationPathNode& left, - const OperationPathNode& right) { - return left.node == right.node && left.argIndex == right.argIndex; -} - -template -inline bool operator!=(const OperationPathNode& left, - const OperationPathNode& right) { - return left.node != right.node || left.argIndex != right.argIndex; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/ordered.hpp b/ct_core/include/ct/external/cppad/cg/ordered.hpp deleted file mode 100644 index 546ca85d2..000000000 --- a/ct_core/include/ct/external/cppad/cg/ordered.hpp +++ /dev/null @@ -1,70 +0,0 @@ -#ifndef CPPAD_CG_ORDERED_INCLUDED -#define CPPAD_CG_ORDERED_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { - -template -bool GreaterThanZero(const cg::CG &x) { - if (!x.isParameter()) { - throw cg::CGException("GreaterThanZero cannot be called for non-parameters"); - } - - return GreaterThanZero(x.getValue()); -} - -template -bool GreaterThanOrZero(const cg::CG &x) { - if (!x.isParameter()) { - throw cg::CGException("GreaterThanOrZero cannot be called for non-parameters"); - } - - return GreaterThanOrZero(x.getValue()); -} - -template -bool LessThanZero(const cg::CG &x) { - if (!x.isParameter()) { - throw cg::CGException("LessThanZero cannot be called for non-parameters"); - } - - return LessThanZero(x.getValue()); -} - -template -bool LessThanOrZero(const cg::CG &x) { - if (!x.isParameter()) { - throw cg::CGException("LessThanOrZero cannot be called for non-parameters"); - } - - return LessThanOrZero(x.getValue()); -} - -template -bool abs_geq(const cg::CG& x, - const cg::CG& y) { - if (!x.isParameter()) { - throw cg::CGException("abs_geq cannot be called for non-parameters (x)"); - } else if (!y.isParameter()) { - throw cg::CGException("abs_geq cannot be called for non-parameters (y)"); - } - - return abs_geq(x.getValue(), y.getValue()); -} - -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/ostream_config_restore.hpp b/ct_core/include/ct/external/cppad/cg/ostream_config_restore.hpp deleted file mode 100644 index 124feaff7..000000000 --- a/ct_core/include/ct/external/cppad/cg/ostream_config_restore.hpp +++ /dev/null @@ -1,51 +0,0 @@ -#ifndef CPPAD_CG_OSTREAM_CONFIG_RESTORE_INCLUDED -#define CPPAD_CG_OSTREAM_CONFIG_RESTORE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2015 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include - -namespace CppAD { -namespace cg { - -class OStreamConfigRestore { -private: - std::ostream& os; - std::ios::fmtflags f; - std::streamsize nf; - std::streamsize nw; -public: - - inline explicit OStreamConfigRestore(std::ostream& os) : - os(os), - f(os.flags()), - nf(os.precision()), - nw(os.width()) { - } - - OStreamConfigRestore(const OStreamConfigRestore &rhs) = delete; - OStreamConfigRestore& operator=(const OStreamConfigRestore& rhs) = delete; - - inline ~OStreamConfigRestore() { - os.flags(f); - os.precision(nf); - os.width(nw); - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/patterns/dependent_pattern_matcher.hpp b/ct_core/include/ct/external/cppad/cg/patterns/dependent_pattern_matcher.hpp deleted file mode 100644 index 4232008e8..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/dependent_pattern_matcher.hpp +++ /dev/null @@ -1,1337 +0,0 @@ -#ifndef CPPAD_CG_DEPENDENT_PATTERN_MATCHER_INCLUDED -#define CPPAD_CG_DEPENDENT_PATTERN_MATCHER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -//#define CPPADCG_PRINT_DEBUG - -namespace CppAD { -namespace cg { - -template -class UniqueEquationPair { -public: - EquationPattern* eq1; - EquationPattern* eq2; -public: - - inline UniqueEquationPair(EquationPattern* e1, EquationPattern* e2) { - if (e1->depRefIndex < e2->depRefIndex) { - eq1 = e1; - eq2 = e2; - } else { - eq1 = e2; - eq2 = e1; - } - } -}; - -template -inline bool operator<(const UniqueEquationPair& p1, const UniqueEquationPair& p2) { - return p1.eq1->depRefIndex < p2.eq1->depRefIndex || (!(p2.eq1->depRefIndex < p1.eq1->depRefIndex) && p1.eq2->depRefIndex < p2.eq2->depRefIndex); -} - -/** - * Finds common patterns in operation graphs - */ -template -class DependentPatternMatcher { -public: - typedef CG CGBase; -private: - - enum class INDEXED_OPERATION_TYPE { - INDEXED, - NONINDEXED, - BOTH - }; - typedef std::pair Indexed2OpCountType; - typedef std::map*, Indexed2OpCountType> > > Dep1Dep2SharedType; - typedef std::pair DepPairType; - typedef std::map*, Indexed2OpCountType>* > > TotalOps2validDepsType; - typedef std::map, TotalOps2validDepsType*> Eq2totalOps2validDepsType; - typedef std::map MaxOps2eq2totalOps2validDepsType; - -private: - CodeHandler* handler_; - CodeHandlerVector varId_; - CodeHandlerVector varIndexed_; // which nodes depend on indexed independent variables - const std::vector >& relatedDepCandidates_; - std::vector dependents_; // a copy - std::vector& independents_; - std::vector*> equations_; - EquationPattern* eqCurr_; - std::map*> dep2Equation_; - std::map*, Loop*> equation2Loop_; - std::vector*> loops_; - /** - * Equations which cannot be in the same loop - */ - std::map*, std::set*> > incompatible_; - /** - * - */ - std::map, Dep1Dep2SharedType> equationShared_; - /** - * maps the original model nodes used as temporary non-indexed variables - * by the loops to an index k - */ - std::map*, size_t> origTemp2Index_; - std::vector > id2Deps; - size_t idCounter_; - /** - * the original shared node ID used to sort shared variables to ensure - * reproducibility between different runs - */ - CodeHandlerVector origShareNodeId_; - /// used to mark visited nodes and indexed nodes - size_t color_; -public: - - /** - * Creates a new DependentPatternMatcher - * - * @param relatedDepCandidates Groups of dependent variable indexes that - * are believed to have the same expression - * pattern. - * @param dependents The dependent variable values - * @param independents The independent variable values - */ - DependentPatternMatcher(const std::vector >& relatedDepCandidates, - const std::vector& dependents, - std::vector& independents) : - handler_(independents[0].getCodeHandler()), - varId_(*handler_), - varIndexed_(*handler_), - relatedDepCandidates_(relatedDepCandidates), - dependents_(dependents), - independents_(independents), - idCounter_(0), - origShareNodeId_(*handler_), - color_(0) { - CPPADCG_ASSERT_UNKNOWN(independents_.size() > 0); - CPPADCG_ASSERT_UNKNOWN(independents_[0].getCodeHandler() != nullptr); - equations_.reserve(relatedDepCandidates_.size()); - origShareNodeId_.adjustSize(); - } - - const std::vector*>& getEquationPatterns() const { - return equations_; - } - - const std::vector*>& getLoops() const { - return loops_; - } - - /** - * Detects common equation patterns and generates a new tape for the - * model using loops. - * This method should only be called once! - * - * @param nonLoopTape The new tape without the loops or nullptr if there - * are no non-indexed expressions in the model - * @param loopTapes The models for each loop (must be deleted by the user) - */ - virtual void generateTapes(LoopFreeModel*& nonLoopTape, - std::set*>& loopTapes) { - - for (size_t j = 0; j < independents_.size(); j++) { - std::vector& info = independents_[j].getOperationNode()->getInfo(); - info.resize(1); - info[0] = j; - } - - findLoops(); - - nonLoopTape = createNewTape(); - - loopTapes.clear(); - for (size_t l = 0; l < loops_.size(); l++) { - Loop* loop = loops_[l]; - loopTapes.insert(loop->releaseLoopModel()); - } - } - - virtual ~DependentPatternMatcher() { - for (size_t l = 0; l < loops_.size(); l++) { - delete loops_[l]; - } - } - -private: - - /** - * Attempts to detect common patterns in the equations and generate - * loops from these patterns. - * - * @return information about the detected loops - */ - virtual std::vector*> findLoops() { - using namespace std; - - size_t rSize = relatedDepCandidates_.size(); - for (size_t r = 0; r < rSize; r++) { - const std::set& candidates = relatedDepCandidates_[r]; - for (size_t iDep : candidates) { - OperationNode* node = dependents_[iDep].getOperationNode(); - if (node != nullptr && node->getOperationType() == CGOpCode::Inv) { - /** - * indexed/nonindexed independents are marked at the - * operation that uses them, therefore currently there - * is no way to make a distinction between - * yi = xi and y_(i+1) = x_(i+1) - * since both operations which use indexed independents - * have no operation, consequently an alias is used - */ - CPPADCG_ASSERT_UNKNOWN(handler_ == dependents_[iDep].getCodeHandler()); - dependents_[iDep] = CG(*handler_->makeNode(CGOpCode::Alias, *node)); - } - } - } - - varId_.adjustSize(); - varId_.fill(0); - - // assign a unique Id to each node - assignIds(); - id2Deps.resize(idCounter_ + 1); - - /** - * Determine the equation patterns - */ - findRelatedVariables(); - - for (EquationPattern* eq : equations_) { - for (size_t depIt : eq->dependents) { - dep2Equation_[depIt] = eq; - } - } - - const size_t eq_size = equations_.size(); - loops_.reserve(eq_size); - - SmartSetPointer > dependentRelations; - std::vector*> dep2Relations(dependents_.size(), nullptr); - map > dependentBlackListRelations; - - /******************************************************************* - * Combine related equations in the same loops - * (equations that share temporary variables) - ******************************************************************/ - /** - * Find and organize relationships - */ - varIndexed_.adjustSize(); - varIndexed_.fill(false); - - for (size_t e = 0; e < eq_size; e++) { - EquationPattern* eq = equations_[e]; - eqCurr_ = eq; - - for (size_t depIt : eq->dependents) { - OperationNode* node = dependents_[depIt].getOperationNode(); - // will define the dependents associated with each operation - markOperationsWithDependent(node, depIt); - } - - /** - * Find shared operations with the previous equation patterns - */ - if (e > 0) { - handler_->startNewOperationTreeVisit(); - - for (size_t depIt : eq->dependents) { - findSharedTemporaries(dependents_[depIt], depIt); // a color is used to mark indexed paths - } - - /** - * clean-up - */ - for (size_t depIt : eq->dependents) { - OperationNode* node = dependents_[depIt].getOperationNode(); - EquationPattern::uncolor(node, varIndexed_); // must uncolor - } - } - - // create a loop for this equation - Loop* loop = new Loop(*eq); - loops_.push_back(loop); - equation2Loop_[eq] = loop; - } - - /******************************************************************* - * Attempt to combine loops with shared variables - ******************************************************************/ - MaxOps2eq2totalOps2validDepsType maxOps2Eq2totalOps2validDeps; - Eq2totalOps2validDepsType eq2totalOps2validDeps; - SmartListPointer totalOps2validDepsMem; - - /** - * First organize pairs of equation patterns with shared variables - * by the maximum number of shared operations among two dependent - * variables. - */ - for (size_t l1 = 0; l1 < loops_.size(); l1++) { - Loop* loop1 = loops_[l1]; - CPPADCG_ASSERT_UNKNOWN(loop1->equations.size() == 1); - EquationPattern* eq1 = *loop1->equations.begin(); - - for (size_t l2 = l1 + 1; l2 < loops_.size(); l2++) { - Loop* loop2 = loops_[l2]; - CPPADCG_ASSERT_UNKNOWN(loop2->equations.size() == 1); - EquationPattern* eq2 = *loop2->equations.begin(); - - UniqueEquationPair eqRel(eq1, eq2); - const auto eqSharedit = equationShared_.find(eqRel); - if (eqSharedit == equationShared_.end()) - continue; // nothing is shared between eq1 and eq2 - - const Dep1Dep2SharedType& dep1Dep2Shared = eqSharedit->second; - - /** - * There are shared variables among the two equation patterns - */ - TotalOps2validDepsType* totalOps2validDeps = new TotalOps2validDepsType(); - totalOps2validDepsMem.push_back(totalOps2validDeps); - size_t maxOps = 0; // the maximum number of shared operations between two dependents - - bool canCombine = true; - - /*************************************************** - * organize relations between dependents - **************************************************/ - for (const auto& itDep1Dep2 : dep1Dep2Shared) { - size_t dep1 = itDep1Dep2.first; - const map*, Indexed2OpCountType> >& dep2Shared = itDep1Dep2.second; - - // multiple deps2 means multiple choices for a relation (only one dep1<->dep2 can be chosen) - for (const auto& itDep2 : dep2Shared) { - size_t dep2 = itDep2.first; - const map*, Indexed2OpCountType>& sharedTmps = itDep2.second; - - size_t totalOps = 0; // the total number of operations performed by shared variables with dep2 - for (const auto& itShared : sharedTmps) { - if (itShared.second.first == INDEXED_OPERATION_TYPE::BOTH) { - /** - * one equation uses this temporary shared - * variable as an indexed variable while the - * other equation does not - */ - canCombine = false; - break; - } else { - totalOps += itShared.second.second; - } - } - - if (!canCombine) break; - - DepPairType depRel(dep1, dep2); - (*totalOps2validDeps)[totalOps][depRel] = &sharedTmps; - maxOps = std::max(maxOps, totalOps); - } - - if (!canCombine) break; - } - - if (canCombine) { - maxOps2Eq2totalOps2validDeps[maxOps][eqRel] = totalOps2validDeps; - eq2totalOps2validDeps[eqRel] = totalOps2validDeps; - } else { - incompatible_[eq1].insert(eq2); - incompatible_[eq2].insert(eq1); - totalOps2validDepsMem.pop_back(); - delete totalOps2validDeps; - } - } - } - - /** - * Try to merge loops with shared variables - */ - typename MaxOps2eq2totalOps2validDepsType::const_reverse_iterator itMaxOps; - for (itMaxOps = maxOps2Eq2totalOps2validDeps.rbegin(); itMaxOps != maxOps2Eq2totalOps2validDeps.rend(); ++itMaxOps) { -#ifdef CPPADCG_PRINT_DEBUG - std::cout << "\n\nmaxOps: " << itMaxOps->first << " count:" << itMaxOps->second.size() << std::endl; -#endif - - for (const auto& itEqPair : itMaxOps->second) { - const UniqueEquationPair& eqRel = itEqPair.first; -#ifdef CPPADCG_PRINT_DEBUG - std::cout << " eq1: " << *eqRel.eq1->dependents.begin() << " eq2: " << *eqRel.eq2->dependents.begin() << std::endl; -#endif - - Loop* loop1 = equation2Loop_.at(eqRel.eq1); - Loop* loop2 = equation2Loop_.at(eqRel.eq2); - - if (loop1 == loop2) - continue; // already done - if (contains(incompatible_, eqRel.eq1, eqRel.eq2)) - continue; // incompatible - - /** - * backup so that it is possible to revert the new relations if - * required - */ - SmartSetPointer > dependentRelationsBak; - for (const set* its : dependentRelations) { - dependentRelationsBak.insert(new set(*its)); - } - - // relationships between dependents for the resulting merged loop - set*> loopRelations; - - set*> indexedLoopRelations; - std::vector*, EquationPattern*> > nonIndexedLoopRelations; - - /** - * All equations from both loops must be compatible - */ - bool compatible = isCompatible(loop1, loop2, - eq2totalOps2validDeps, - dep2Relations, dependentBlackListRelations, dependentRelations, - loopRelations, indexedLoopRelations, nonIndexedLoopRelations); - - if (compatible) { - // merge the two loops - - // update the loop of the equations - for (EquationPattern* itle : loop2->equations) { - equation2Loop_[itle] = loop1; - } - loop1->merge(*loop2, indexedLoopRelations, nonIndexedLoopRelations); - - typename std::vector*>::iterator it = std::find(loops_.begin(), loops_.end(), loop2); - CPPADCG_ASSERT_UNKNOWN(it != loops_.end()); - loops_.erase(it); - delete loop2; - - loop1->setLinkedDependents(loopRelations); - - // relation between loop1 and loop2 done! - } else { - // restore dependent relations - dependentRelations.s.swap(dependentRelationsBak.s); - // map each dependent to the relation set where it is present - std::fill(dep2Relations.begin(), dep2Relations.end(), nullptr); - for (set* relation : dependentRelations) { - for (size_t itd : *relation) { - dep2Relations[itd] = relation; - } - } - - } - - } - } - - /** - * Determine the number of iterations in each loop - */ - for (size_t l = 0; l < loops_.size(); l++) { - loops_[l]->generateDependentLoopIndexes(dep2Equation_); - } - - /******************************************************************* - * Attempt to combine unrelated loops - ******************************************************************/ - if (!loops_.empty()) { - for (size_t l1 = 0; l1 < loops_.size() - 1; l1++) { - Loop* loop1 = loops_[l1]; - for (size_t l2 = l1 + 1; l2 < loops_.size();) { - Loop* loop2 = loops_[l2]; - - bool canMerge = loop1->getIterationCount() == loop2->getIterationCount(); - if (canMerge) { - // check if there are equations in the blacklist - canMerge = !find(loop1, loop2, incompatible_); - } - - if (canMerge) { - loop1->mergeEqGroups(*loop2); - loops_.erase(loops_.begin() + l2); - delete loop2; - } else { - l2++; - } - } - } - } - - size_t l_size = loops_.size(); - - /** - * assign indexes (k) to temporary variables (non-indexed) used by loops - */ - for (size_t l = 0; l < l_size; l++) { - Loop* loop = loops_[l]; - - //Generate a local model for the loop - loop->createLoopModel(dependents_, independents_, dep2Equation_, origTemp2Index_); - } - - /** - * clean-up evaluation order - */ - resetHandlerCounters(); - - return loops_; - } - - /** - * Determines whether or not two loops which shared temporary variables - * can be merged. - * - * @param loop1 First loop - * @param loop2 Second loop - * @return true if the loops should be merged into a single loop - */ - inline bool isCompatible(Loop* loop1, - Loop* loop2, - const Eq2totalOps2validDepsType& eq2totalOps2validDeps, - std::vector* >& dep2Relations, - std::map >& dependentBlackListRelations, - SmartSetPointer >& dependentRelations, - std::set*>& loopRelations, - std::set*>& indexedLoopRelations, - std::vector*, EquationPattern*> >& nonIndexedLoopRelations) { - using namespace std; - - bool compatible = true; - - /** - * Must order equation pairs property according to the highest - * number of shared operations - */ - map, TotalOps2validDepsType*> > totalOp2eq; - - for (EquationPattern* eq1 : loop1->equations) { - - for (EquationPattern* eq2 : loop2->equations) { - - UniqueEquationPair eqRel(eq1, eq2); - - typename Eq2totalOps2validDepsType::const_iterator eqSharedit = eq2totalOps2validDeps.find(eqRel); - if (eqSharedit == eq2totalOps2validDeps.end()) - continue; // nothing is shared between eq1 and eq2 - - - size_t maxOps = eqSharedit->second->rbegin()->first; - totalOp2eq[maxOps][eqRel] = eqSharedit->second; - } - } - - typename map, TotalOps2validDepsType*> >::const_reverse_iterator itr; - for (itr = totalOp2eq.rbegin(); itr != totalOp2eq.rend(); ++itr) { - // loop shared operation count - - for (const auto& itEq : itr->second) { - EquationPattern* eq1 = itEq.first.eq1; - EquationPattern* eq2 = itEq.first.eq2; - TotalOps2validDepsType& totalOps2validDeps = *itEq.second; - - /*************************************************** - * attempt to combine dependents which share the - * highest number of operations first - **************************************************/ - typename map*, Indexed2OpCountType>* > >::const_reverse_iterator itOp2Dep2Shared; - for (itOp2Dep2Shared = totalOps2validDeps.rbegin(); itOp2Dep2Shared != totalOps2validDeps.rend(); ++itOp2Dep2Shared) { -#ifdef CPPADCG_PRINT_DEBUG - std::cout << " operation count: " << itOp2Dep2Shared->first << " relations: " << itOp2Dep2Shared->second.size() << std::endl; -#endif - for (const auto& itDep2Shared : itOp2Dep2Shared->second) { - DepPairType depRel = itDep2Shared.first; - size_t dep1 = depRel.first; - size_t dep2 = depRel.second; - - const map*, Indexed2OpCountType>& shared = *itDep2Shared.second; - /** - * this dep1 <-> dep2 is used as a reference to combine - * the two equations in the same loop - */ - compatible = findDepRelations(eq1, dep1, eq2, dep2, shared, - dep2Relations, dependentBlackListRelations, dependentRelations); - if (!compatible) break; - } - - loopRelations.clear(); - - if (compatible) { - /** - * there has to be at least one iteration with all equation patterns - */ - std::vector*> loops(2); - loops[0] = loop1; - loops[1] = loop2; - bool nonIndexedOnly = true; - for (size_t l = 0; l < 2; l++) { - Loop* loop = loops[l]; - for (EquationPattern* eq : loop->equations) { // equation - for (size_t dep : eq->dependents) { // dependent - if (dep2Relations[dep] != nullptr) { - loopRelations.insert(dep2Relations[dep]); - nonIndexedOnly = false; - } - } - } - } - - - - if (nonIndexedOnly) { - nonIndexedLoopRelations.push_back(std::make_pair(eq1, eq2)); - } else { - // there are shared indexed temporary variables - compatible = false; - size_t nNonIndexedRel1 = loop1->getLinkedEquationsByNonIndexedCount(); - size_t nNonIndexedRel2 = loop2->getLinkedEquationsByNonIndexedCount(); - size_t requiredSize = loop1->equations.size() + loop2->equations.size() - nNonIndexedRel1 - nNonIndexedRel2; - - for (set* relations : loopRelations) { - if (relations->size() == requiredSize) { - compatible = true; - break; - } - } -#ifdef CPPADCG_PRINT_DEBUG - if (compatible) { - std::cout << " loopRelations:"; - print(loopRelations); - std::cout << std::endl; - } -#endif - } - } - - if (!compatible) break; - } - - if (!compatible) { - incompatible_[eq1].insert(eq2); - incompatible_[eq2].insert(eq1); - break; - } else { - indexedLoopRelations.insert(eq1); - indexedLoopRelations.insert(eq2); - } - } - - if (!compatible) break; - } - - return compatible; - } - - /** - * Determines the relations between the dependents of two equation - * patterns using two dependents as reference and the shared variables - * among the two patterns - * - * @return true if these equation patterns are compatible - * (if they can be in the same loop) - */ - bool findDepRelations(EquationPattern* eq1, - size_t dep1, - EquationPattern* eq2, - size_t dep2, - const std::map*, Indexed2OpCountType>& sharedNodes, - std::vector* >& dep2Relations, - std::map >& dependentBlackListRelations, - SmartSetPointer >& dependentRelations) { - using namespace std; - - for (const auto& itShared : sharedNodes) { - OperationNode* sharedNode = itShared.first; - - // checks independents - bool compatible = canCombineEquations(*eq1, dep1, *eq2, dep2, *sharedNode, - dep2Relations, dependentBlackListRelations, dependentRelations); - - if (!compatible) return false; - } - - return true; - } - - void groupByLoopEqOp(EquationPattern* eq, - std::map*, std::map*, std::map*, bool> > > >& loopSharedTemps, - const std::map*, std::set >& opShared, - bool indexed) { - using namespace std; - - for (OperationNode* shared : opShared) { - const set& deps = id2Deps[varId_[*shared]]; - - for (size_t dep : deps) { - EquationPattern* otherEq = dep2Equation_.at(dep); - if (eq != otherEq) { - Loop* loop = equation2Loop_.at(otherEq); - // the original ID (saved in evaluation order) is used to sort shared variables - // to ensure reproducibility between different runs - loopSharedTemps[loop][otherEq][origShareNodeId_[shared]] = std::make_pair(shared, indexed); - } - } - } - } - - /** - * Creates a new tape for the model without the equations in the loops - * and with some extra dependents for the temporary variables used by - * loops. - * - * @return The new tape without loop equations - */ - virtual LoopFreeModel* createNewTape() { - CPPADCG_ASSERT_UNKNOWN(handler_ == independents_[0].getCodeHandler()); - - size_t m = dependents_.size(); - std::vector inLoop(m, false); - size_t eqInLoopCount = 0; - - /** - * Create the new tape - */ - size_t l_size = loops_.size(); - - for (size_t l = 0; l < l_size; l++) { - Loop* loop = loops_[l]; - LoopModel* loopModel = loop->getModel(); - - /** - * determine which equations belong to loops - */ - const std::vector >& ldeps = loopModel->getDependentIndexes(); - for (size_t eq = 0; eq < ldeps.size(); eq++) { - for (size_t it = 0; it < ldeps[eq].size(); it++) { - const LoopPosition& pos = ldeps[eq][it]; - if (pos.original != std::numeric_limits::max()) {// some equations are not present in all iteration - inLoop[pos.original] = true; - eqInLoopCount++; - } - } - } - } - - /** - * create a new smaller tape - */ - assert(m >= eqInLoopCount); - size_t nonLoopEq = m - eqInLoopCount; - std::vector nonLoopDeps(nonLoopEq + origTemp2Index_.size()); - - if (nonLoopDeps.size() == 0) - return nullptr; // there are no equations outside the loops - - /** - * Place the dependents that do not belong to a loop - */ - size_t inl = 0; - std::vector depTape2Orig(nonLoopEq); - if (eqInLoopCount < m) { - for (size_t i = 0; i < inLoop.size(); i++) { - if (!inLoop[i]) { - depTape2Orig[inl] = i; - nonLoopDeps[inl++] = dependents_[i]; - } - } - } - CPPADCG_ASSERT_UNKNOWN(inl == nonLoopEq); - - /** - * Place new dependents for the temporary variables used by the loops - */ - for (const auto& itTmp : origTemp2Index_) { - size_t k = itTmp.second; - nonLoopDeps[nonLoopEq + k] = handler_->createCG(Argument(*itTmp.first)); - } - - /** - * Generate the new tape by going again through the operations - */ - Evaluator evaluator(*handler_); - - // set atomic functions - const std::map* >& atomicsOrig = handler_->getAtomicFunctions(); - std::map* > atomics; - atomics.insert(atomicsOrig.begin(), atomicsOrig.end()); - evaluator.addAtomicFunctions(atomics); - - std::vector > x(independents_.size()); - for (size_t j = 0; j < x.size(); j++) { - if (independents_[j].isValueDefined()) - x[j] = independents_[j].getValue(); - } - - CppAD::Independent(x); - std::vector > y = evaluator.evaluate(x, nonLoopDeps); - - std::unique_ptr > tapeNoLoops(new ADFun()); - tapeNoLoops->Dependent(y); - - return new LoopFreeModel(tapeNoLoops.release(), depTape2Orig); - } - - std::vector*> findRelatedVariables() { - eqCurr_ = nullptr; - CodeHandlerVector varColor(*handler_); - color_ = 1; // used to mark visited nodes - - varColor.adjustSize(); - varColor.fill(0); - - size_t rSize = relatedDepCandidates_.size(); - for (size_t r = 0; r < rSize; r++) { - const std::set& candidates = relatedDepCandidates_[r]; - std::set used; - - eqCurr_ = nullptr; - - std::set::const_iterator itRef; - for (itRef = candidates.begin(); itRef != candidates.end(); ++itRef) { - size_t iDepRef = *itRef; - - // check if it has already been used - if (used.find(iDepRef) != used.end()) { - continue; - } - - if (eqCurr_ == nullptr || used.size() > 0) { - eqCurr_ = new EquationPattern(dependents_[iDepRef], iDepRef); - equations_.push_back(eqCurr_); - } - - std::set::const_iterator it = itRef; - for (++it; it != candidates.end(); ++it) { - size_t iDep = *it; - // check if it has already been used - if (used.find(iDep) != used.end()) { - continue; - } - - if (eqCurr_->testAdd(iDep, dependents_[iDep], color_, varColor)) { - used.insert(iDep); - } - } - - if (eqCurr_->dependents.size() == 1) { - // nothing found :( - delete eqCurr_; - eqCurr_ = nullptr; - equations_.pop_back(); - } - } - } - - /** - * Determine the independents that don't change from iteration to - * iteration - */ - for (size_t eq = 0; eq < equations_.size(); eq++) { - equations_[eq]->detectNonIndexedIndependents(); - } - - return equations_; - } - - /** - * Finds nodes which can be shared with other equation patterns - * - * @param value The CG object to visit - * @param depIndex The index of the dependent variable - * @return true if this operation is indexed - */ - inline bool findSharedTemporaries(const CG& value, - size_t depIndex) { - OperationNode* depNode = value.getOperationNode(); - size_t opCount = 0; - if (findSharedTemporaries(depNode, depIndex, opCount)) { - varIndexed_[*depNode] = true; - return true; - } - return false; - } - - /** - * Finds nodes which can be shared with other equation patterns - * - * @param node The node to visit - * @param depIndex The index of the dependent variable - * @param opCount The number of operations which must be performed to - * generate this node - * @return true if this operation is indexed (for the current equation pattern) - */ - inline bool findSharedTemporaries(OperationNode* node, - size_t depIndex, - size_t& opCount) { - if (node == nullptr) - return false; // nothing to do - - if (handler_->isVisited(*node)) { - opCount++; // this operation - return varIndexed_[*node]; - } - - handler_->markVisited(*node); - - bool indexedOperation = false; - - size_t localOpCount = 1; - const std::vector >& args = node->getArguments(); - size_t arg_size = args.size(); - for (size_t a = 0; a < arg_size; a++) { - OperationNode*argOp = args[a].getOperation(); - if (argOp != nullptr) { - if (argOp->getOperationType() != CGOpCode::Inv) { - indexedOperation |= findSharedTemporaries(argOp, depIndex, localOpCount); - } else { - indexedOperation |= !eqCurr_->containsConstantIndependent(node, a); - } - } - } - - opCount += localOpCount; - - varIndexed_[*node] = indexedOperation; // mark this operation as being indexed or not-indexed - - size_t id = varId_[*node]; - std::set& deps = id2Deps[id]; - - if (deps.size() > 1 && node->getOperationType() != CGOpCode::Inv) { - /** - * Temporary variable - */ - for (size_t otherDep : deps) { - - EquationPattern* otherEquation = dep2Equation_.at(otherDep); - if (otherEquation != eqCurr_) { - /** - * temporary variable shared with a different loop - */ - UniqueEquationPair eqPair(eqCurr_, otherEquation); - Dep1Dep2SharedType& relation = equationShared_[eqPair]; - - std::map*, Indexed2OpCountType>* reldepdep; - if (eqPair.eq1 == eqCurr_) - reldepdep = &relation[depIndex][otherDep]; - else - reldepdep = &relation[otherDep][depIndex]; - - INDEXED_OPERATION_TYPE expected = indexedOperation ? INDEXED_OPERATION_TYPE::INDEXED : INDEXED_OPERATION_TYPE::NONINDEXED; - typename std::map*, Indexed2OpCountType>::iterator itIndexedType = reldepdep->find(node); - if (itIndexedType == reldepdep->end()) { - (*reldepdep)[node] = Indexed2OpCountType(expected, localOpCount); - } else if (itIndexedType->second.first != expected) { - itIndexedType->second.first = INDEXED_OPERATION_TYPE::BOTH; - } - - break; - } - } - } - - return indexedOperation; - } - - /** - * Marks a node (and all other nodes used by it) as being used by a - * given dependent variable. - * - * @param node The node being visited - * @param dep Dependent variable index - */ - inline void markOperationsWithDependent(const OperationNode* node, - size_t dep) { - if (node == nullptr || node->getOperationType() == CGOpCode::Inv) - return; // nothing to do - - size_t id = varId_[*node]; - - std::set& deps = id2Deps[id]; - - if (deps.size() == 0) { - deps.insert(dep); // here for the first time - } else { - std::pair < std::set::iterator, bool> added = deps.insert(dep); - if (!added.second) { - return; // already been here - } - } - - const std::vector >& args = node->getArguments(); - size_t arg_size = args.size(); - for (size_t i = 0; i < arg_size; i++) { - markOperationsWithDependent(args[i].getOperation(), dep); - } - } - - void assignIds() { - idCounter_ = 1; - - size_t rSize = relatedDepCandidates_.size(); - for (size_t r = 0; r < rSize; r++) { - const std::set& candidates = relatedDepCandidates_[r]; - - for (size_t it : candidates) { - assignIds(dependents_[it].getOperationNode()); - } - } - } - - void assignIds(OperationNode* node) { - if (node == nullptr || varId_[*node] > 0) - return; - - varId_[*node] = idCounter_; - origShareNodeId_.adjustSize(*node); - origShareNodeId_[*node] = idCounter_; - idCounter_++; - - const std::vector >& args = node->getArguments(); - size_t arg_size = args.size(); - for (size_t i = 0; i < arg_size; i++) { - assignIds(args[i].getOperation()); - } - } - - void resetHandlerCounters() { - size_t rSize = relatedDepCandidates_.size(); - for (size_t r = 0; r < rSize; r++) { - const std::set& candidates = relatedDepCandidates_[r]; - - for (size_t it : candidates) { - resetHandlerCounters(dependents_[it].getOperationNode()); - } - } - } - - void resetHandlerCounters(OperationNode* node) { - if (node == nullptr || varId_[*node] == 0 || origShareNodeId_[*node] == 0) - return; - - varId_[*node] = 0; - origShareNodeId_[*node] = 0; - - const std::vector >& args = node->getArguments(); - size_t arg_size = args.size(); - for (size_t i = 0; i < arg_size; i++) { - resetHandlerCounters(args[i].getOperation()); - } - } - - static bool find(Loop* loop1, Loop* loop2, - const std::map*, std::set*> >& blackList) { - for (EquationPattern* iteq1 : loop1->equations) { - - const auto itBlack = blackList.find(iteq1); - if (itBlack != blackList.end()) { - - for (EquationPattern* iteq2 : loop2->equations) { - if (itBlack->second.find(iteq2) != itBlack->second.end()) { - return true; // found - } - } - } - } - - return false; - } - - template - static inline bool contains(const std::map >& map, T eq1, T eq2) { - typename std::map >::const_iterator itb1; - itb1 = map.find(eq1); - if (itb1 != map.end()) { - if (itb1->second.find(eq2) != itb1->second.end()) { - return true; - } - } - return false; - } - - bool canCombineEquations(const EquationPattern& eq1, - size_t dep1, - const EquationPattern& eq2, - size_t dep2, - OperationNode& sharedTemp, - std::vector* >& dep2Relations, - std::map >& dependentBlackListRelations, - SmartSetPointer >& dependentRelations) { - using namespace std; - - // must have indexed independents at the same locations in all equations - const set*> opWithIndepArgs = eq1.findOperationsUsingIndependents(sharedTemp); - - // must have indexed independents at the same locations in both equations - for (const OperationNode* op : opWithIndepArgs) { - // get indexed independent variable information - // - equation 1 - typename map*, OperationIndexedIndependents >::const_iterator indexed1It; - OperationNode* op1 = eq1.operationEO2Reference.at(dep1).at(op); // convert to the reference of equation 1 - indexed1It = eq1.indexedOpIndep.op2Arguments.find(op1); - - // - equation 2 - typename map*, OperationIndexedIndependents >::const_iterator indexed2It; - OperationNode* op2 = eq2.operationEO2Reference.at(dep2).at(op); // convert to the reference of equation 2 - indexed2It = eq2.indexedOpIndep.op2Arguments.find(op2); - - /** - * Compare the iterations where this operation is used in both equation patterns - */ - if (indexed1It == eq1.indexedOpIndep.op2Arguments.end()) { - if (indexed2It != eq2.indexedOpIndep.op2Arguments.end()) { - return false; // indexed in one equation but non-indexed in the other - } - } else { - if (indexed2It == eq2.indexedOpIndep.op2Arguments.end()) { - return false; // indexed in one equation but non-indexed in the other - } - - /** - * Indexed path in both equations - */ - const OperationIndexedIndependents& indexed1Ops = indexed1It->second; - const OperationIndexedIndependents& indexed2Ops = indexed2It->second; - - size_t a1Size = indexed1Ops.arg2Independents.size(); - if (a1Size != indexed2Ops.arg2Independents.size()) { // there must be the same number of arguments - return false; - } - - for (size_t a = 0; a < a1Size; a++) { - const map*>& eq1Dep2Indep = indexed1Ops.arg2Independents[a]; - const map*>& eq2Dep2Indep = indexed2Ops.arg2Independents[a]; - - if (eq1Dep2Indep.empty() != eq2Dep2Indep.empty()) - return false; // one is indexed and the other is non-indexed - - // it has to be possible to match dependents from the two equation patterns - - if (eq1Dep2Indep.empty()) { - continue; // not indexed - } - - // indexed independent variable - - // invert eq1Dep2Indep into eq1Indep2Dep - typedef map*, size_t, IndependentNodeSorter > MapIndep2Dep; - MapIndep2Dep eq1Indep2Dep; - typename MapIndep2Dep::iterator hint = eq1Indep2Dep.begin(); - for (const auto& d2i : eq1Dep2Indep) { - hint = eq1Indep2Dep.insert(hint, std::make_pair(d2i.second, d2i.first)); - hint++; // assume that the relation dep<->indep is always ascending - } - - typename map*, size_t>::const_iterator itHint = eq1Indep2Dep.begin(); - - // check all iterations/dependents - for (const auto& d2i : eq2Dep2Indep) { - size_t dep2 = d2i.first; - const OperationNode* indep = d2i.second; - typename map*, size_t>::const_iterator it; - if (itHint->first == indep) { - /** - * assumes that the both relations - * (indep<->dep1 and dep2<->indep) are in - * ascending order which is commonly true - */ - it = itHint; - itHint++; - } else { - it = eq1Indep2Dep.find(indep); - } - - if (it != eq1Indep2Dep.end()) { - size_t dep1 = it->second; - - // check if this relation was previous excluded - std::map >::const_iterator itBlackL = dependentBlackListRelations.find(dep1); - if (itBlackL != dependentBlackListRelations.end() && itBlackL->second.find(dep2) != itBlackL->second.end()) { - return false; // these dependents cannot be in the same iteration - } - - bool related = makeDependentRelation(eq1, dep1, eq2, dep2, - dep2Relations, dependentRelations); - if (!related) - return false; - - } else { - // equation pattern 1 does not have any iteration with indep from dep2 - - // there is no need to have the same number of iterations in both equations! - // but remember that these dependents cannot be in the same iteration from now on - dependentBlackListRelations[dep2].insert(eq1.dependents.begin(), eq1.dependents.end()); - } - } - - } - - } - - } - - return true; - } - - bool isNonIndexed(const EquationPattern& eq2, - size_t dep2, - OperationNode& sharedTemp) { - using namespace std; - - - // must have indexed independents at the same locations in all equations - const set*> opWithIndepArgs = EquationPattern::findOperationsUsingIndependents(sharedTemp); - - for (const OperationNode* op : opWithIndepArgs) { - // get indexed independent variable information - // - equation 2 - OperationNode* op2 = eq2.operationEO2Reference.at(dep2).at(op); // convert to the reference of equation 2 - - const auto indexed2It = eq2.indexedOpIndep.op2Arguments.find(op2); - if (indexed2It != eq2.indexedOpIndep.op2Arguments.end()) { - return false; // indexed in one equation but non-indexed in the other - } - } - - return true; - } - - bool makeDependentRelation(const EquationPattern& eq1, - size_t dep1, - const EquationPattern& eq2, - size_t dep2, - std::vector* >& dep2Relations, - SmartSetPointer >& dependentRelations) { - using namespace std; - - set* related1 = dep2Relations[dep1]; - set* related2 = dep2Relations[dep2]; - - // check if relations were established with a different dependent from the same equation pattern - if (related1 != nullptr) { - // dependent 1 already in a relation set - - if (related2 != nullptr) { - // both dependents belong to previously existing relations sets - - if (related1 == related2) - return true; // already done - - // relations must be merged (if possible)! - // merge related2 into related1 - bool canMerge = true; - - for (size_t dep3 : *related2) { - - const EquationPattern& eq3 = *dep2Equation_.at(dep3); - // make sure no other dependent from the same equation pattern was already in this relation set - for (size_t it : eq3.dependents) { - if (it != dep3 && related1->find(it) != related1->end()) { - canMerge = false; // relation with a dependent from a different iteration! - break; - //return false; - } - } - - if (!canMerge) - break; - } - - if (canMerge) { - for (size_t dep3 : *related2) { - related1->insert(dep3); - dep2Relations[dep3] = related1; - } - - dependentRelations.erase(related2); - delete related2; - } - /** - * when it is not possible to merge due to a dependent - * variable from another iteration already belonging to a - * dependent variable relation (iteration) the new relation - * is not added and as a consequence there will be some - * repeated operations - */ - - } else { - if (related1->find(dep2) == related1->end()) { - // make sure no other dependent from the same equation pattern was already in this relation set - bool canMerge = true; - for (size_t it : eq2.dependents) { - if (it != dep2 && related1->find(it) != related1->end()) { - canMerge = false; // relation with a dependent from a different iteration! - break; - } - } - - if (canMerge) { - related1->insert(dep2); - dep2Relations[dep2] = related1; - } - /** - * when it is not possible to merge due to a dependent - * variable from another iteration already belonging to a - * dependent variable relation (iteration) the new relation - * is not added and as a consequence there will be some - * repeated operations - */ - } - } - - } else if (related2 != nullptr) { - // dependent 2 already in a relation set - - // make sure no other dependent from the same equation pattern was already in this relation set - bool canMerge = true; - for (size_t it : eq1.dependents) { - if (it != dep1 && related2->find(it) != related2->end()) { - canMerge = false; // relation with a dependent from a different iteration! - break; - //return false; - } - } - - if (canMerge) { - related2->insert(dep1); - dep2Relations[dep1] = related2; - } - /** - * when it is not possible to merge due to a dependent - * variable from another iteration already belonging to a - * dependent variable relation (iteration) the new relation - * is not added and as a consequence there will be some - * repeated operations - */ - - - } else { - // dependent 1 and dependent 2 not in any relation set - set* related = new std::set(); - dependentRelations.insert(related); - related->insert(dep1); - related->insert(dep2); - dep2Relations[dep1] = related; - dep2Relations[dep2] = related; - } - - return true; - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif diff --git a/ct_core/include/ct/external/cppad/cg/patterns/equation_group.hpp b/ct_core/include/ct/external/cppad/cg/patterns/equation_group.hpp deleted file mode 100644 index 016b334ac..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/equation_group.hpp +++ /dev/null @@ -1,139 +0,0 @@ -#ifndef CPPAD_CG_EQUATION_GROUP_INCLUDED -#define CPPAD_CG_EQUATION_GROUP_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * A groups of equations which share common temporary variables - */ -template -class EquationGroup { -public: - /** - * The equations in this group - */ - std::set*> equations; - /** - * Which dependents (equation indexes) must be evaluated at the same - * time due to shared indexed temporary variables - */ - std::vector > linkedDependents; - /** - * Which equation pattern should be evaluated at the same - * time due to shared non-indexed temporary variables - */ - std::vector*> > linkedEquationsByNonIndexedRel; - std::set*> linkedEquationsByNonIndexed; // only equation which do not have any shared indexed variables - /** - * The evaluated dependents in each loop iteration - * ([iteration 1]{dep1, dep3, ...}; [iteration 2]{dep5, dep6, ...}; ...) - */ - std::vector > iterationDependents; - /** - * Reference iteration where all equations are present - */ - size_t refIteration; -public: - - inline void findReferenceIteration() { - CPPADCG_ASSERT_UNKNOWN(!iterationDependents.empty()); - - for (size_t it = 0; it < iterationDependents.size(); it++) { - if (iterationDependents[it].size() == equations.size()) { - refIteration = it; - return; - } - } - - CPPADCG_ASSERT_UNKNOWN(false); - } - - inline long findIndexedLinkedDependent(size_t dep) const { - size_t size = linkedDependents.size(); - for (size_t pos = 0; pos < size; pos++) { - const std::set& sameIndex = linkedDependents[pos]; - if (sameIndex.find(dep) != sameIndex.end()) { - return pos; - } - } - - return -1; - } - - inline size_t getLinkedEquationsByNonIndexedCount() const { - return linkedEquationsByNonIndexed.size(); - } - - inline size_t findNonIndexedLinkedRel(EquationPattern* eq) const { - size_t size = linkedEquationsByNonIndexedRel.size(); - for (size_t pos = 0; pos < size; pos++) { - if (linkedEquationsByNonIndexedRel[pos].find(eq) != linkedEquationsByNonIndexedRel[pos].end()) { - return pos; - } - } - - return -1; - } - - inline void addLinkedEquationsByNonIndexed(EquationPattern* eq1, - EquationPattern* eq2) { - linkedEquationsByNonIndexed.insert(eq1); - linkedEquationsByNonIndexed.insert(eq2); - - size_t size = linkedEquationsByNonIndexedRel.size(); - size_t pos1 = size; - size_t pos2 = size; - for (size_t pos = 0; pos < size; pos++) { - if (linkedEquationsByNonIndexedRel[pos].find(eq1) != linkedEquationsByNonIndexedRel[pos].end()) { - pos1 = pos; - break; - } - } - for (size_t pos = 0; pos < size; pos++) { - if (linkedEquationsByNonIndexedRel[pos].find(eq2) != linkedEquationsByNonIndexedRel[pos].end()) { - pos2 = pos; - break; - } - } - - if (pos1 == pos2) { - if (pos1 == size) { - linkedEquationsByNonIndexedRel.resize(size + 1); - linkedEquationsByNonIndexedRel[size].insert(eq1); - linkedEquationsByNonIndexedRel[size].insert(eq2); - } - } else if (pos1 < size) { - if (pos2 < size) { - // must merge - linkedEquationsByNonIndexedRel[pos1].insert(linkedEquationsByNonIndexedRel[pos2].begin(), linkedEquationsByNonIndexedRel[pos2].end()); - linkedEquationsByNonIndexedRel.erase(linkedEquationsByNonIndexedRel.begin() + pos2); - } else { - linkedEquationsByNonIndexedRel[pos1].insert(eq2); - } - - } else { - CPPADCG_ASSERT_UNKNOWN(pos2 < size); - linkedEquationsByNonIndexedRel[pos2].insert(eq1); - } - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/patterns/equation_pattern.hpp b/ct_core/include/ct/external/cppad/cg/patterns/equation_pattern.hpp deleted file mode 100644 index ad1f42292..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/equation_pattern.hpp +++ /dev/null @@ -1,503 +0,0 @@ -#ifndef CPPAD_CG_EQUATION_PATTERN_INCLUDED -#define CPPAD_CG_EQUATION_PATTERN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Holds information on which independents are used by which - * dependent in an equation pattern - */ -template -class OperationIndexedIndependents { -public: - typedef std::map*> MapDep2Indep_type; - /** - * maps the argument index to the several independents used in different - * equations with the same pattern - * argument index -> (iteration or dependent using it) -> independent - */ - std::vector arg2Independents; -}; - -template -class IndexedIndependent { -public: - std::map*, OperationIndexedIndependents > op2Arguments; -public: - - const OperationIndexedIndependents& arguments(const OperationNode* operation) const { - return op2Arguments.at(operation); - } - - bool isIndexedOperationArgument(const OperationNode* node, size_t argIndex) const { - const auto itIndexes = op2Arguments.find(node); - if (itIndexes == op2Arguments.end()) { - return false; - } - const OperationIndexedIndependents& indexedArgs = itIndexes->second; - return indexedArgs.arg2Independents.size() > argIndex && !indexedArgs.arg2Independents[argIndex].empty(); - } - -}; - -/** - * Group of variables with the same evaluation pattern - * (same equation different variables) - */ -template -class EquationPattern { -public: - const CG& depRef; // dependent reference - const size_t depRefIndex; - std::set dependents; - /** - * maps node ID used by all dependents to the operations of the - * reference dependent - * [dependent index][op] = reference operation - */ - std::map*, OperationNode*> > operationEO2Reference; - // std::map*> > operationEO2Reference; - /** - * Maps the operations that used an indexed independents as direct - * arguments - * (reference operation -> argument indexes -> dependent <-> independents) - */ - IndexedIndependent indexedOpIndep; - /** - * reference operation -> non indexed argument positions - */ - std::map*, std::set > constOperationIndependents; - -private: - CodeHandler* const handler_; - size_t currDep_; - size_t minColor_; - size_t cmpColor_; -public: - - explicit EquationPattern(const CG& ref, - size_t iDepRef) : - depRef(ref), - depRefIndex(iDepRef), - dependents {iDepRef}, - handler_(ref.getCodeHandler()) { - } - - EquationPattern(const EquationPattern& other) = delete; - - EquationPattern& operator=(const EquationPattern& rhs) = delete; - - bool testAdd(size_t iDep2, - const CG& dep2, - size_t& minColor, - CodeHandlerVector& varColor) { - IndexedIndependent independentsBackup = indexedOpIndep; - std::map*, std::set > constOperationIndependentsBackup = constOperationIndependents; - std::map*, OperationNode*> > operation2ReferenceBackup = operationEO2Reference; - - currDep_ = iDep2; - minColor_ = minColor; - cmpColor_ = minColor_; - - bool equals = comparePath(depRef, dep2, iDep2, varColor); - - minColor = cmpColor_; - - if (equals) { - dependents.insert(iDep2); - - return true; // matches the reference pattern - } else { - // restore - indexedOpIndep.op2Arguments.swap(independentsBackup.op2Arguments); - constOperationIndependents.swap(constOperationIndependentsBackup); - operationEO2Reference.swap(operation2ReferenceBackup); - - return false; // cannot be added - } - } - - inline void findIndexedPath(size_t dep, - const std::vector >& depVals, - CodeHandlerVector& varIndexed, - std::set*>& indexedOperations) { - findIndexedPath(depRef, depVals[dep], varIndexed, indexedOperations); - } - - std::set*> findOperationsUsingIndependents(OperationNode& node) const { - std::set*> ops; - - handler_->startNewOperationTreeVisit(); - - findOperationsWithIndeps(node, ops); - - return ops; - } - - static inline void uncolor(OperationNode* node, - CodeHandlerVector& varIndexed) { - if (node == nullptr || !varIndexed[*node]) - return; - - varIndexed[*node] = false; - - const std::vector >& args = node->getArguments(); - size_t size = args.size(); - for (size_t a = 0; a < size; a++) { - uncolor(args[a].getOperation(), varIndexed); - } - } - - inline bool containsConstantIndependent(const OperationNode* operation, size_t argumentIndex) const { - const auto it = constOperationIndependents.find(operation); - if (it != constOperationIndependents.end()) { - if (it->second.find(argumentIndex) != it->second.end()) { - return true; - } - } - return false; - } - - /** - * Determine which independent variables in the loop model do not - * require an index (always the same for all iterations) - */ - inline void detectNonIndexedIndependents() { - typedef typename OperationIndexedIndependents::MapDep2Indep_type MapIndep2Dep_type; - - // loop operations using independents - typename std::map*, OperationIndexedIndependents >::iterator itop2a = indexedOpIndep.op2Arguments.begin(); - while (itop2a != indexedOpIndep.op2Arguments.end()) { - const OperationNode* parentOp = itop2a->first; - OperationIndexedIndependents& arg2It = itop2a->second; - - bool emptyOp = true; - - // loop the arguments - size_t aSize = arg2It.arg2Independents.size(); - for (size_t argIndex = 0; argIndex < aSize; argIndex++) { - MapIndep2Dep_type& dep2Ind = arg2It.arg2Independents[argIndex]; - - if (dep2Ind.empty()) - continue; // argument does not use independents - - // loop dependents (iterations) - bool isIndexed = false; - typename MapIndep2Dep_type::const_iterator itDep2Ind = dep2Ind.begin(); - const OperationNode* indep = itDep2Ind->second; - - for (++itDep2Ind; itDep2Ind != dep2Ind.end(); ++itDep2Ind) { - if (indep != itDep2Ind->second) { - isIndexed = true; - break; - } - } - - if (!isIndexed) { - // make it a non indexed independent - constOperationIndependents[parentOp].insert(argIndex); - - // remove it from the indexed independents - dep2Ind.clear(); - } else { - emptyOp = false; - } - - } - - if (emptyOp) { - indexedOpIndep.op2Arguments.erase(itop2a++); - } else { - ++itop2a; - } - - } - - } - - virtual ~EquationPattern() { - } - -private: - - bool comparePath(const CG& dep1, - const CG& dep2, - size_t dep2Index, - CodeHandlerVector& varColor) { - CodeHandler* h1 = dep1.getCodeHandler(); - CodeHandler* h2 = dep2.getCodeHandler(); - - if (h1 != h2) { - if (h1 != nullptr && h2 != nullptr) - throw CGException("Only one code handler allowed"); - return false; - } - - if (dep1.isParameter() && dep2.isParameter()) { - return dep1.getValue() == dep2.getValue(); - - } else if (dep1.isVariable() && dep2.isVariable()) { - OperationNode* depRefOp = dep1.getOperationNode(); - OperationNode* dep2Op = dep2.getOperationNode(); - CPPADCG_ASSERT_UNKNOWN(depRefOp->getOperationType() != CGOpCode::Inv); - - return comparePath(depRefOp, dep2Op, dep2Index, varColor); - } - - return false; - } - - bool comparePath(OperationNode* scRef, - OperationNode* sc2, - size_t dep2, - CodeHandlerVector& varColor) { - saveOperationReference(dep2, sc2, scRef); - if (dependents.size() == 1) { - saveOperationReference(depRefIndex, scRef, scRef); - } - - while (scRef->getOperationType() == CGOpCode::Alias) { - CPPADCG_ASSERT_KNOWN(scRef->getArguments().size() == 1, "Invalid number of arguments for alias"); - OperationNode* sc = scRef->getArguments()[0].getOperation(); - if (sc != nullptr && sc->getOperationType() == CGOpCode::Inv) break; // an alias is used to distinguish between indexed dependents and indexed independents - scRef = sc; - } - while (sc2->getOperationType() == CGOpCode::Alias) { - CPPADCG_ASSERT_KNOWN(sc2->getArguments().size() == 1, "Invalid number of arguments for alias"); - OperationNode* sc = sc2->getArguments()[0].getOperation(); - if (sc != nullptr && sc->getOperationType() == CGOpCode::Inv) break; // an alias is used to distinguish between indexed dependents and indexed independents - sc2 = sc; - } - - // check if these nodes where visited before - if (varColor[*sc2] >= minColor_ && varColor[*scRef] >= minColor_) { - /** - * been here before for both nodes - * warning: if one would return varColor[*sc2] == varColor[*scRef] - * it could fail to detect some patterns! e.g.: - * it ref -> v1 + v1 + v2 - * it 2 -> v3 + v1 + v1 - * where v1, v2, v3 have the same expression pattern but - * correspond to different nodes - */ - if (varColor[*sc2] == varColor[*scRef]) - return true; - } - varColor[*scRef] = cmpColor_; - varColor[*sc2] = cmpColor_; - cmpColor_++; - - - if (scRef->getOperationType() != sc2->getOperationType()) { - return false; - } - - CPPADCG_ASSERT_UNKNOWN(scRef->getOperationType() != CGOpCode::Inv); - - const std::vector& info1 = scRef->getInfo(); - const std::vector& info2 = sc2->getInfo(); - if (info1.size() != info2.size()) { - return false; - } - - for (size_t e = 0; e < info1.size(); e++) { - if (info1[e] != info2[e]) { - return false; - } - } - - const std::vector >& args1 = scRef->getArguments(); - const std::vector >& args2 = sc2->getArguments(); - size_t size = args1.size(); - if (size != args2.size()) { - return false; - } - for (size_t a = 0; a < size; a++) { - const Argument& a1 = args1[a]; - const Argument& a2 = args2[a]; - - if (a1.getParameter() != nullptr) { - if (a2.getParameter() == nullptr || *a1.getParameter() != *a2.getParameter()) - return false; - } else { - if (a2.getOperation() == nullptr) { - return false; - } - OperationNode* argRefOp = a1.getOperation(); - OperationNode* arg2Op = a2.getOperation(); - bool related; - if (argRefOp->getOperationType() == CGOpCode::Inv) { - related = saveIndependent(scRef, a, argRefOp, arg2Op); - } else { - related = comparePath(argRefOp, arg2Op, dep2, varColor); - } - - if (!related) - return false; - } - } - - return true; // same pattern - } - - inline void saveOperationReference(size_t dep2, - const OperationNode* sc2, - OperationNode* scRef) { - operationEO2Reference[dep2][sc2] = scRef; - } - - bool saveIndependent(const OperationNode* parentOp, - size_t argIndex, - const OperationNode* argRefOp, - const OperationNode* arg2Op) { - if (argRefOp->getOperationType() != CGOpCode::Inv || arg2Op->getOperationType() != CGOpCode::Inv) { - return false; - } - - /** - * Must consider that the independent might change from iteration to - * iteration (even if now it won't) - */ - const auto it = constOperationIndependents.find(parentOp); - if (it != constOperationIndependents.end()) { - if (it->second.find(argIndex) != it->second.end()) { - return false; - } - } - - OperationIndexedIndependents& opIndexedIndep = indexedOpIndep.op2Arguments[parentOp]; - opIndexedIndep.arg2Independents.resize(parentOp != nullptr ? parentOp->getArguments().size() : 1); - - std::map*>& dep2Indeps = opIndexedIndep.arg2Independents[argIndex]; - if (dep2Indeps.empty()) - dep2Indeps[depRefIndex] = argRefOp; - dep2Indeps[currDep_] = arg2Op; - - return true; // same pattern - } - - inline void findIndexedPath(const CG& depRef, - const CG& dep2, - CodeHandlerVector& varIndexed, - std::set*>& indexedOperations) { - if (depRef.isVariable() && dep2.isVariable()) { - OperationNode* depRefOp = depRef.getOperationNode(); - OperationNode* dep2Op = dep2.getOperationNode(); - if (depRefOp->getOperationType() != CGOpCode::Inv) { - findIndexedPath(depRefOp, dep2Op, varIndexed, indexedOperations); - } else { - - typename std::map*, OperationIndexedIndependents >::iterator itop2a; - itop2a = indexedOpIndep.op2Arguments.find(nullptr); - if (itop2a != indexedOpIndep.op2Arguments.end() && !itop2a->second.arg2Independents[0].empty()) { - // depends on an index - indexedOperations.insert(nullptr); - } - } - } - } - - inline bool findIndexedPath(const OperationNode* scRef, - OperationNode* sc2, - CodeHandlerVector& varIndexed, - std::set*>& indexedOperations) { - - while (scRef->getOperationType() == CGOpCode::Alias) { - CPPADCG_ASSERT_KNOWN(scRef->getArguments().size() == 1, "Invalid number of arguments for alias"); - OperationNode* sc = scRef->getArguments()[0].getOperation(); - if (sc != nullptr && sc->getOperationType() == CGOpCode::Inv) break; // an alias is used to distinguish between indexed dependents and indexed independents - scRef = sc; - } - while (sc2->getOperationType() == CGOpCode::Alias) { - CPPADCG_ASSERT_KNOWN(sc2->getArguments().size() == 1, "Invalid number of arguments for alias"); - OperationNode* sc = sc2->getArguments()[0].getOperation(); - if (sc != nullptr && sc->getOperationType() == CGOpCode::Inv) break; // an alias is used to distinguish between indexed dependents and indexed independents - sc2 = sc; - } - - CPPADCG_ASSERT_UNKNOWN(scRef->getOperationType() == sc2->getOperationType()); - - const std::vector >& argsRef = scRef->getArguments(); - - typename std::map*, OperationIndexedIndependents >::iterator itop2a; - bool searched = false; - bool indexedDependentPath = false; - bool usesIndexedIndependent = false; // directly uses an indexed independent - - size_t size = argsRef.size(); - for (size_t a = 0; a < size; a++) { - OperationNode* argRefOp = argsRef[a].getOperation(); - if (argRefOp != nullptr) { - bool indexedArg = false; - if (argRefOp->getOperationType() == CGOpCode::Inv) { - // same independent variable can be used in multiple iterations - if (!searched) { - itop2a = indexedOpIndep.op2Arguments.find(scRef); - searched = true; - } - if (itop2a != indexedOpIndep.op2Arguments.end() && !itop2a->second.arg2Independents[a].empty()) { - // depends on an index - indexedArg = true; - indexedDependentPath = true; - usesIndexedIndependent = true; - } - } - - if (!indexedArg) { - const std::vector >& args2 = sc2->getArguments(); - CPPADCG_ASSERT_UNKNOWN(size == args2.size()); - indexedDependentPath |= findIndexedPath(argsRef[a].getOperation(), args2[a].getOperation(), varIndexed, indexedOperations); - } - } - } - - varIndexed[*sc2] = indexedDependentPath; - - if (usesIndexedIndependent) - indexedOperations.insert(sc2); - - return indexedDependentPath; - } - - void findOperationsWithIndeps(OperationNode& node, - std::set*>& ops) const { - if (handler_->isVisited(node)) - return; // been here before - - handler_->markVisited(node); - - const std::vector >& args = node.getArguments(); - size_t size = args.size(); - for (size_t a = 0; a < size; a++) { - OperationNode* argOp = args[a].getOperation(); - if (argOp != nullptr) { - if (argOp->getOperationType() == CGOpCode::Inv) { - ops.insert(&node); - } else { - findOperationsWithIndeps(*argOp, ops); - } - } - } - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/patterns/independent_node_sorter.hpp b/ct_core/include/ct/external/cppad/cg/patterns/independent_node_sorter.hpp deleted file mode 100644 index b98062ff8..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/independent_node_sorter.hpp +++ /dev/null @@ -1,62 +0,0 @@ -#ifndef CPPAD_CG_INDEPENDENT_SORTER_INCLUDED -#define CPPAD_CG_INDEPENDENT_SORTER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Class used to sort independent variable nodes in ascending order - * according to their index (saved in the info vector of the nodes) - */ -template -class IndependentNodeSorter { -public: - - /** - * @return true if the first node goes before the second node - */ - bool operator()(const OperationNode* node1, - const OperationNode* node2) { - CPPADCG_ASSERT_UNKNOWN(node1 == nullptr || node1->getInfo().size() == 1); - CPPADCG_ASSERT_UNKNOWN(node2 == nullptr || node2->getInfo().size() == 1); - CPPADCG_ASSERT_UNKNOWN(node1 == nullptr || node1->getOperationType() == CGOpCode::Inv); - CPPADCG_ASSERT_UNKNOWN(node2 == nullptr || node2->getOperationType() == CGOpCode::Inv); - - // some variables are not used in all iterations - if (node1 == nullptr) { - if (node2 == nullptr) { - return false; - } - return true; - } else if (node2 == nullptr) { - return false; - } - - size_t index1 = node1->getInfo()[0]; - size_t index2 = node2->getInfo()[0]; - if (index1 < index2) - return true; - else //if (index1 >= index2) - return false; - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/patterns/index/index_pattern.hpp b/ct_core/include/ct/external/cppad/cg/patterns/index/index_pattern.hpp deleted file mode 100644 index d6c392498..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/index/index_pattern.hpp +++ /dev/null @@ -1,62 +0,0 @@ -#ifndef CPPAD_CG_INDEX_PATTERN_INCLUDED -#define CPPAD_CG_INDEX_PATTERN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Generic index pattern - */ -class IndexPattern { -public: - - virtual IndexPatternType getType() const = 0; - - virtual void getSubIndexes(std::set& indexes) const = 0; - - inline virtual ~IndexPattern() { - } - - /*********************************************************************** - * static methods - **********************************************************************/ - /** - * Detects the index pattern for the provided points (y = f(x)) - * - * @param indexX the index of the independents (x) - * @param x2y maps the independents to the dependents (indexes[x] = y ) - * @return the generated index pattern (must be deleted by user) - */ - template - static inline IndexPattern* detect(const VectorSizeT& x2y); - - /** - * Detects the index pattern for the provided points (y = f(x)) - * - * @param indexX the index of the independents (x) - * @param x2y maps the independents to the dependents (x,y) - * @return the generated index pattern (must be deleted by user) - */ - static inline IndexPattern* detect(const std::map& x2y); - - static inline bool isConstant(const IndexPattern& ip); -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/patterns/index/index_pattern_impl.hpp b/ct_core/include/ct/external/cppad/cg/patterns/index/index_pattern_impl.hpp deleted file mode 100644 index 1872ae1ee..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/index/index_pattern_impl.hpp +++ /dev/null @@ -1,64 +0,0 @@ -#ifndef CPPAD_CG_INDEX_PATTERN_IMPL_INCLUDED -#define CPPAD_CG_INDEX_PATTERN_IMPL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -IndexPattern* IndexPattern::detect(const VectorSizeT& x2y) { - CPPADCG_ASSERT_UNKNOWN(x2y.size() > 0); - - size_t maxCount = std::min(std::max(3ul, x2y.size() / 4), 8ul); - std::map linearSections = SectionedIndexPattern::detectLinearSections(x2y, maxCount); - - if (linearSections.size() == 1) { - return linearSections.begin()->second; - } else if (!linearSections.empty()) { - return new SectionedIndexPattern(linearSections); - } else { - return new Random1DIndexPattern(x2y); - } - -} - -IndexPattern* IndexPattern::detect(const std::map& x2y) { - CPPADCG_ASSERT_UNKNOWN(!x2y.empty()); - - size_t maxCount = std::min(std::max(3ul, x2y.size() / 4), 8ul); - std::map linearSections = SectionedIndexPattern::detectLinearSections(x2y, maxCount); - - if (linearSections.size() == 1) { - return linearSections.begin()->second; - } else if (!linearSections.empty()) { - return new SectionedIndexPattern(linearSections); - } else { - return new Random1DIndexPattern(x2y); - } -} - -inline bool IndexPattern::isConstant(const IndexPattern& ip) { - if (ip.getType() == IndexPatternType::Linear) { - const LinearIndexPattern& lip = static_cast (ip); - return lip.getLinearSlopeDy() == 0; - } - return false; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/patterns/index/linear_index_pattern.hpp b/ct_core/include/ct/external/cppad/cg/patterns/index/linear_index_pattern.hpp deleted file mode 100644 index 526fb5951..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/index/linear_index_pattern.hpp +++ /dev/null @@ -1,84 +0,0 @@ -#ifndef CPPAD_CG_LINEAR_INDEX_PATTERN_INCLUDED -#define CPPAD_CG_LINEAR_INDEX_PATTERN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Linear pattern y = ((x - offset) / dx) * dy + b - */ -class LinearIndexPattern : public IndexPattern { -protected: - long xOffset_; - // slope - long dy_; - long dx_; - // constant term - long b_; -public: - - inline LinearIndexPattern(long xOffset, long dy, long dx, long b) : - xOffset_(xOffset), - dy_(dy), - dx_(dx), - b_(b) { - } - - inline long getXOffset()const { - return xOffset_; - } - - inline long getLinearSlopeDy() const { - return dy_; - } - - inline void setLinearSlopeDy(long dy) { - dy_ = dy; - } - - inline long getLinearSlopeDx() const { - return dx_; - } - - inline long getLinearConstantTerm() const { - return b_; - } - - inline void setLinearConstantTerm(long b) { - b_ = b; - } - - inline virtual IndexPatternType getType() const override { - return IndexPatternType::Linear; - } - - inline virtual void getSubIndexes(std::set& indexes) const override { - // nothing to add - } - - inline long evaluate(long x) const { - return ((x - xOffset_) / dx_) * dy_ + b_; - } - - inline virtual ~LinearIndexPattern() { - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/patterns/index/plane_2d_index_pattern.hpp b/ct_core/include/ct/external/cppad/cg/patterns/index/plane_2d_index_pattern.hpp deleted file mode 100644 index f47871ce5..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/index/plane_2d_index_pattern.hpp +++ /dev/null @@ -1,195 +0,0 @@ -#ifndef CPPAD_CG_PLANE_2D_INDEX_PATTERN_INCLUDED -#define CPPAD_CG_PLANE_2D_INDEX_PATTERN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * A plane index pattern (2D) defined by two index patterns for each index - * coordinate - * - * z = f1(x) + f2(y) - */ -class Plane2DIndexPattern : public IndexPattern { -protected: - /** - * maps the start of the linear section (first x) to the linear pattern - */ - IndexPattern* pattern1_; - IndexPattern* pattern2_; -public: - - inline Plane2DIndexPattern(IndexPattern* pattern1, - IndexPattern* pattern2) : - pattern1_(pattern1), - pattern2_(pattern2) { - CPPADCG_ASSERT_UNKNOWN(pattern1_ != nullptr || pattern2_ != nullptr); - } - - Plane2DIndexPattern(const Plane2DIndexPattern& orig) = delete; - - inline const IndexPattern* getPattern1() const { - return pattern1_; - } - - inline const IndexPattern* getPattern2() const { - return pattern2_; - } - - inline virtual IndexPatternType getType() const override { - return IndexPatternType::Plane2D; - } - - inline virtual void getSubIndexes(std::set& indexes) const override { - if (pattern1_ != nullptr) { - indexes.insert(pattern1_); - pattern1_->getSubIndexes(indexes); - } - if (pattern2_ != nullptr) { - indexes.insert(pattern2_); - pattern2_->getSubIndexes(indexes); - } - } - - inline virtual ~Plane2DIndexPattern() { - delete pattern1_; - delete pattern2_; - } - - /*********************************************************************** - * static methods - **********************************************************************/ - - static inline Plane2DIndexPattern* detectPlane2D(const std::map >& x2y2z) { - /** - * try to fit a combination of two patterns: - * z = fStart(x) + flit(y); - */ - - if (x2y2z.size() == 1) { - // only one x -> fit z to y - const std::map& y2z = x2y2z.begin()->second; - return new Plane2DIndexPattern(nullptr, IndexPattern::detect(y2z)); - } - - // perhaps there is always only one y - size_t y = x2y2z.begin()->second.begin()->first; - std::map x2z; - std::map >::const_iterator itx2y2z; - for (itx2y2z = x2y2z.begin(); itx2y2z != x2y2z.end(); ++itx2y2z) { - size_t x = itx2y2z->first; - const std::map& y2z = itx2y2z->second; - - if (y2z.size() != 1 || - y != y2z.begin()->first) { - x2z.clear(); // not always the same y - break; - } - - size_t z = y2z.begin()->second; - x2z[x] = z; - } - - if (!x2z.empty()) { - return new Plane2DIndexPattern(IndexPattern::detect(x2z), nullptr); - } - - /** - * try to fit a combination of two patterns: - * z = fStart(x) + flit(y); - */ - std::map x2zStart; - std::map y2zOffset; - - for (itx2y2z = x2y2z.begin(); itx2y2z != x2y2z.end(); ++itx2y2z) { - size_t x = itx2y2z->first; - const std::map& y2z = itx2y2z->second; - - size_t zFirst = y2z.begin()->second; - x2zStart[x] = zFirst; - - std::map::const_iterator ity2z; - - for (ity2z = y2z.begin(); ity2z != y2z.end(); ++ity2z) { - size_t y = ity2z->first; - size_t offset = ity2z->second - zFirst; - std::map::const_iterator itY2zOffset = y2zOffset.find(y); - if (itY2zOffset == y2zOffset.end()) { - y2zOffset[y] = offset; - } else if (itY2zOffset->second != offset) { - return nullptr; // does not fit the pattern - } - } - } - - /** - * try to detect a pattern for the initial iteration index based on x - */ - std::unique_ptr fx; - - std::map startSections = SectionedIndexPattern::detectLinearSections(x2zStart, 2); - if (startSections.empty()) { - return nullptr; // does not fit the pattern - } - - // detected a pattern for the first z based on x - if (startSections.size() == 1) { - fx = std::unique_ptr (startSections.begin()->second); - } else { - fx = std::unique_ptr (new SectionedIndexPattern(startSections)); - } - - /** - * try to detect a pattern for the following iterations - * based on the local loop index (local index != model index) - */ - std::map sections = SectionedIndexPattern::detectLinearSections(y2zOffset, 2); - if (sections.empty()) { - return nullptr; // does not fit the pattern - } - - // detected a pattern for the z offset based on y - std::unique_ptr fy; - if (sections.size() == 1) { - fy = std::unique_ptr (sections.begin()->second); - } else { - fy = std::unique_ptr (new SectionedIndexPattern(sections)); - } - - // simplify when both patterns are constant - if (fx->getType() == IndexPatternType::Linear && fy->getType() == IndexPatternType::Linear) { - LinearIndexPattern* ipx = static_cast (fx.get()); - LinearIndexPattern* ipy = static_cast (fy.get()); - - if (ipx->getLinearSlopeDy() == 0 && ipy->getLinearSlopeDy() == 0) { - /** - * only need to keep one - */ - ipx->setLinearConstantTerm(ipx->getLinearConstantTerm() + ipy->getLinearConstantTerm()); - fy.reset(); - } - } - - return new Plane2DIndexPattern(fx.release(), fy.release()); - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/patterns/index/random_1d_index_pattern.hpp b/ct_core/include/ct/external/cppad/cg/patterns/index/random_1d_index_pattern.hpp deleted file mode 100644 index c98ff5e81..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/index/random_1d_index_pattern.hpp +++ /dev/null @@ -1,57 +0,0 @@ -#ifndef CPPAD_CG_RANDOM_1D_INDEX_PATTERN_INCLUDED -#define CPPAD_CG_RANDOM_1D_INDEX_PATTERN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Random pattern - */ -class Random1DIndexPattern : public RandomIndexPattern { -protected: - std::map indexes_; - std::string name_; -public: - - template - inline Random1DIndexPattern(const VectorSizeT& x2y) { - CPPADCG_ASSERT_UNKNOWN(x2y.size() > 0); - for (size_t x = 0; x < x2y.size(); x++) - indexes_[x] = x2y[x]; - } - - inline Random1DIndexPattern(const std::map& x2y) : - indexes_(x2y) { - CPPADCG_ASSERT_UNKNOWN(!indexes_.empty()); - } - - inline virtual IndexPatternType getType() const override { - return IndexPatternType::Random1D; - } - - inline const std::map& getValues() const { - return indexes_; - } - - inline virtual ~Random1DIndexPattern() { - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/patterns/index/random_2d_index_pattern.hpp b/ct_core/include/ct/external/cppad/cg/patterns/index/random_2d_index_pattern.hpp deleted file mode 100644 index 85465bf0c..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/index/random_2d_index_pattern.hpp +++ /dev/null @@ -1,50 +0,0 @@ -#ifndef CPPAD_CG_RANDOM_2D_INDEX_PATTERN_INCLUDED -#define CPPAD_CG_RANDOM_2D_INDEX_PATTERN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Random pattern using two indexes - */ -class Random2DIndexPattern : public RandomIndexPattern { -protected: - std::map > indexes_; - std::string name_; -public: - - inline Random2DIndexPattern(const std::map >& x2y2z) : - indexes_(x2y2z) { - CPPADCG_ASSERT_UNKNOWN(!indexes_.empty()); - } - - inline virtual IndexPatternType getType() const override { - return IndexPatternType::Random2D; - } - - inline const std::map >& getValues() const { - return indexes_; - } - - inline virtual ~Random2DIndexPattern() { - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/patterns/index/random_index_pattern.hpp b/ct_core/include/ct/external/cppad/cg/patterns/index/random_index_pattern.hpp deleted file mode 100644 index c85e852bf..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/index/random_index_pattern.hpp +++ /dev/null @@ -1,48 +0,0 @@ -#ifndef CPPAD_CG_RANDOM_INDEX_PATTERN_INCLUDED -#define CPPAD_CG_RANDOM_INDEX_PATTERN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Random pattern - */ -class RandomIndexPattern : public IndexPattern { -protected: - std::string name_; -public: - - inline virtual void getSubIndexes(std::set& indexes) const override { - // nothing to add - } - - inline const std::string& getName() const { - return name_; - } - - inline void setName(const std::string& name) { - name_ = name; - } - - inline virtual ~RandomIndexPattern() { - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/patterns/index/sectioned_index_pattern.hpp b/ct_core/include/ct/external/cppad/cg/patterns/index/sectioned_index_pattern.hpp deleted file mode 100644 index 0bb519b2c..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/index/sectioned_index_pattern.hpp +++ /dev/null @@ -1,222 +0,0 @@ -#ifndef CPPAD_CG_SECTIONED_INDEX_PATTERN_INCLUDED -#define CPPAD_CG_SECTIONED_INDEX_PATTERN_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Several linear patterns - */ -class SectionedIndexPattern : public IndexPattern { -protected: - /** - * maps the start of the linear section (first x) to the linear pattern - */ - std::map sections_; -public: - - inline SectionedIndexPattern(const std::map& sections) : - sections_(sections) { - } - - inline const std::map& getLinearSections() const { - return sections_; - } - - inline virtual IndexPatternType getType() const override { - return IndexPatternType::Sectioned; - } - - inline virtual void getSubIndexes(std::set& indexes) const override { - for (const auto& it : sections_) { - indexes.insert(it.second); - it.second->getSubIndexes(indexes); - } - } - - inline virtual ~SectionedIndexPattern() { - deleteIndexPatterns(sections_); - } - - /*********************************************************************** - * static methods - **********************************************************************/ - - template - static inline std::map detectLinearSections(const VectorSizeT& indexes, - size_t maxCount = 0) { - CPPADCG_ASSERT_UNKNOWN(indexes.size() > 0); - - long dx = 1; - long xOffset = 0; - - LinearIndexPattern* prevPattern = nullptr; - size_t prevXStart = 0; - - SmartMapValuePointer linearSections; - size_t xStart = 0; - while (xStart != indexes.size()) { - long dy, b; - size_t lastLinear; - if (xStart + 1 == indexes.size()) { - dy = 0; - b = indexes[xStart]; - lastLinear = xStart + 1; - } else { - dy = long(indexes[xStart + 1]) - indexes[xStart]; - b = long(indexes[xStart]) - dy * xStart; - lastLinear = indexes.size(); - for (size_t x = xStart + 2; x < indexes.size(); x++) { - if (indexes[x] != dy * x + b) { - lastLinear = x; - break; - } - } - } - - LinearIndexPattern* p = new LinearIndexPattern(xOffset, dy, dx, b); - if (dy == 0 && prevPattern != nullptr) { // constant - // can we take the last element out of the previous section? - while (xStart > 0 && prevPattern->evaluate(xStart - 1) == b) { - // yes - xStart--; - if (prevXStart + 1 == xStart) { - // it has only one element -> make it a constant section - size_t bb = prevPattern->evaluate(prevXStart); - prevPattern->setLinearSlopeDy(0); - prevPattern->setLinearConstantTerm(bb); - } - } - } - linearSections[xStart] = p; - - prevXStart = xStart; - prevPattern = p; - xStart = lastLinear; - - if (linearSections.size() == maxCount && xStart != indexes.size()) { - // over the limit -> stop - return std::map(); // empty - } - } - - return linearSections.release(); - } - - static inline std::map detectLinearSections(const std::map& x2y, - size_t maxCount = 0) { - typedef std::map::const_iterator c_iter; - - SmartMapValuePointer linearSections; - - LinearIndexPattern* prevPattern = nullptr; - c_iter prevStart = x2y.begin(); - - c_iter pStart = x2y.begin(); - while (pStart != x2y.end()) { - c_iter pNextSection = x2y.end(); - c_iter p1 = pStart; - ++p1; - - long xOffset, dy, dx, b; - if (p1 == x2y.end()) { - xOffset = 0; - dy = 0; - dx = 1; - b = pStart->second; - pNextSection = p1; - - } else { - long x0 = pStart->first; - long y0 = pStart->second; - - dy = long(p1->second) - y0; - if (dy != 0) { - dx = long(p1->first) - x0; - xOffset = x0 % dx; - // y = ((x - offset) / dx) * dy + b - b = y0 - ((x0 - xOffset) / dx) * dy; - } else { - dx = 1; - xOffset = 0; - b = y0; - } - - for (std::map::const_iterator itp = p1; itp != x2y.end(); ++itp) { - size_t x = itp->first; - size_t y = itp->second; - - if (y != ((x - xOffset) / dx) * dy + b) { - pNextSection = itp; - break; - } - } - } - - LinearIndexPattern* p = new LinearIndexPattern(xOffset, dy, dx, b); - size_t xStart = pStart->first; - if (dy == 0 && prevPattern != nullptr) { // constant - // can we take the last element from the previous section? - - while (pStart != x2y.begin()) { - c_iter prevBack = pStart; - --prevBack; // the values at the end of the previous section - if (prevPattern->evaluate(prevBack->first) != b) - break; // no - - // yes - --pStart; - xStart = pStart->first; - c_iter prevStartN = prevStart; - prevStartN++; - if (prevStartN == pStart) { - // it has only one element -> make it a constant section - size_t bb = prevPattern->evaluate(prevStart->first); - prevPattern->setLinearSlopeDy(0); - prevPattern->setLinearConstantTerm(bb); - } - } - } - linearSections[xStart] = p; - - prevStart = pStart; - prevPattern = p; - pStart = pNextSection; - - if (linearSections.size() == maxCount && pStart != x2y.end()) { - // over the limit -> stop - return std::map(); // empty - } - } - - return linearSections.release(); - } - -private: - - static inline void deleteIndexPatterns(std::map& sections) { - for (const auto& it : sections) { - delete it.second; - } - sections.clear(); - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/patterns/iter_equation_group.hpp b/ct_core/include/ct/external/cppad/cg/patterns/iter_equation_group.hpp deleted file mode 100644 index f0c7ce95c..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/iter_equation_group.hpp +++ /dev/null @@ -1,258 +0,0 @@ -#ifndef CPPAD_CG_ITER_EQUATION_GROUP_INCLUDED -#define CPPAD_CG_ITER_EQUATION_GROUP_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Group of equations present at the same iterations - */ -template -class IterEquationGroup { -public: - typedef CppAD::cg::CG CGB; - typedef Argument Arg; - typedef std::pair pairss; -private: - static const std::vector > EMPTYVECTORSETSS; - static const std::vector > EMPTYVECTORSETS; - static const std::map > EMPTYMAPSETS; -public: - /// iteration group index/ID - size_t index; - /// equations indexes in tape of the loop model - std::set tapeI; - /// iterations which only have these equations defined - std::set iterations; - /// - LoopModel* model; -private: - /** - * Hessian sparsity pattern of the tape - */ - std::vector > hessTapeSparsity_; - bool hessSparsity_; - /** - * indexed Hessian elements - * [{orig J1, orig J2}] -> [iteration -> [{tape J1, tape J2}]] - */ - std::map > > hessOrig2Iter2TapeJ1TapeJ2_; - /** - * indexed Hessian elements - * [{orig J1, orig J2}] -> [iteration -> [{tape J1}]] - */ - std::map > > hessOrig2Iter2TapeJ1OrigJ2_; - /** - * non-indexed Hessian elements - * [{orig J1, orig J2}] -> [iteration -> [{tape J2}]] - */ - std::map > > hessOrig2Iter2OrigJ1TapeJ2_; - /** - * non-indexed Hessian elements - * [{orig J1, orig J2}] - */ - std::set hessOrigJ1OrigJ2_; - /** - * temporary Hessian elements - * [{k1, orig J2}] -> [tape J2 -> [{iteration }]] - */ - std::map > > hessOrig2TempTapeJ22Iter_; -public: - - inline IterEquationGroup() : - index(std::numeric_limits::max()), // not really required - model(nullptr), - hessSparsity_(false) { - } - - inline void evalHessianSparsity() { - if (hessSparsity_) { - return; // already evaluated - } - - CPPADCG_ASSERT_UNKNOWN(model != nullptr); - size_t iterationCount = model->getIterationCount(); - - const std::vector >& indexedIndepIndexes = model->getIndexedIndepIndexes(); - const std::vector& nonIndexedIndepIndexes = model->getNonIndexedIndepIndexes(); - const std::vector& temporaryIndependents = model->getTemporaryIndependents(); - - ADFun& fun = model->getTape(); - - hessTapeSparsity_ = hessianSparsitySet >, CGB>(fun, tapeI); - - /** - * make a database of the Hessian elements - */ - size_t nIndexed = indexedIndepIndexes.size(); - size_t nNonIndexed = nonIndexedIndepIndexes.size(); - size_t nTemp = temporaryIndependents.size(); - - for (size_t iter : iterations) { - /** - * indexed tapeJ1 - */ - for (size_t tapeJ1 = 0; tapeJ1 < nIndexed; tapeJ1++) { - const std::set& hessRow = hessTapeSparsity_[tapeJ1]; - size_t j1 = indexedIndepIndexes[tapeJ1][iter].original; - - std::set ::const_iterator itTape2; - for (itTape2 = hessRow.begin(); itTape2 != hessRow.end() && *itTape2 < nIndexed; ++itTape2) { - size_t j2 = indexedIndepIndexes[*itTape2][iter].original; - pairss orig(j1, j2); - pairss tapeTape(tapeJ1, *itTape2); - std::vector >& iterations = hessOrig2Iter2TapeJ1TapeJ2_[orig]; - iterations.resize(iterationCount); - iterations[iter].insert(tapeTape); - } - - for (; itTape2 != hessRow.end() && *itTape2 < nIndexed + nNonIndexed; ++itTape2) { - size_t j2 = nonIndexedIndepIndexes[*itTape2 - nIndexed].original; - pairss orig(j1, j2); - std::vector >& iterations = hessOrig2Iter2TapeJ1OrigJ2_[orig]; - iterations.resize(iterationCount); - iterations[iter].insert(tapeJ1); - } - } - - /** - * non-indexed tapeJ1 - */ - for (size_t tapeJ1 = nIndexed; tapeJ1 < nIndexed + nNonIndexed; tapeJ1++) { - const std::set& hessRow = hessTapeSparsity_[tapeJ1]; - size_t j1 = nonIndexedIndepIndexes[tapeJ1 - nIndexed].original; - - std::set ::const_iterator itTape2; - for (itTape2 = hessRow.begin(); itTape2 != hessRow.end() && *itTape2 < nIndexed; ++itTape2) { - size_t j2 = indexedIndepIndexes[*itTape2][iter].original; - pairss orig(j1, j2); - std::vector >& iterations = hessOrig2Iter2OrigJ1TapeJ2_[orig]; - iterations.resize(iterationCount); - iterations[iter].insert(*itTape2); - } - - for (; itTape2 != hessRow.end() && *itTape2 < nIndexed + nNonIndexed; ++itTape2) { - size_t j2 = nonIndexedIndepIndexes[*itTape2 - nIndexed].original; - pairss orig(j1, j2); - hessOrigJ1OrigJ2_.insert(orig); - } - } - - /** - * temporaries tapeJ1 - */ - for (size_t tapeJ1 = nIndexed + nNonIndexed; tapeJ1 < nIndexed + nNonIndexed + nTemp; tapeJ1++) { - const std::set& hessRow = hessTapeSparsity_[tapeJ1]; - size_t k1 = temporaryIndependents[tapeJ1 - nIndexed - nNonIndexed].original; - - std::set ::const_iterator itTape2; - for (itTape2 = hessRow.begin(); itTape2 != hessRow.end() && *itTape2 < nIndexed; ++itTape2) { - size_t j2 = indexedIndepIndexes[*itTape2][iter].original; - pairss pos(k1, j2); - std::map >& var2iters = hessOrig2TempTapeJ22Iter_[pos]; - var2iters[*itTape2].insert(iter); - } - - } - } - - hessSparsity_ = true; - - } - - inline const std::vector >& getHessianSparsity() const { - return hessTapeSparsity_; - } - - /** - * - * @param origJ1 - * @param origJ2 - * @return maps each iteration to the pair of tape indexes present in - * the Hessian - */ - inline const std::vector >& getHessianIndexedIndexedTapeIndexes(size_t origJ1, - size_t origJ2) const { - pairss orig(origJ1, origJ2); - - std::map > >::const_iterator it; - it = hessOrig2Iter2TapeJ1TapeJ2_.find(orig); - if (it != hessOrig2Iter2TapeJ1TapeJ2_.end()) { - return it->second; - } else { - return EMPTYVECTORSETSS; - } - } - - inline const std::vector >& getHessianIndexedNonIndexedTapeIndexes(size_t origJ1, - size_t origJ2) const { - pairss orig(origJ1, origJ2); - - std::map > > ::const_iterator it; - it = hessOrig2Iter2TapeJ1OrigJ2_.find(orig); - if (it != hessOrig2Iter2TapeJ1OrigJ2_.end()) { - return it->second; - } else { - return EMPTYVECTORSETS; - } - } - - inline const std::vector >& getHessianNonIndexedIndexedTapeIndexes(size_t origJ1, - size_t origJ2) const { - pairss orig(origJ1, origJ2); - - std::map > >::const_iterator it; - it = hessOrig2Iter2OrigJ1TapeJ2_.find(orig); - if (it != hessOrig2Iter2OrigJ1TapeJ2_.end()) { - return it->second; - } else { - return EMPTYVECTORSETS; - } - } - - inline const std::set >& getHessianNonIndexedNonIndexedIndexes() const { - return hessOrigJ1OrigJ2_; - } - - inline const std::map >& getHessianTempIndexedTapeIndexes(size_t k1, - size_t origJ2) const { - pairss pos(k1, origJ2); - - std::map > >::const_iterator it; - it = hessOrig2TempTapeJ22Iter_.find(pos); - if (it != hessOrig2TempTapeJ22Iter_.end()) { - return it->second; - } else { - return EMPTYMAPSETS; - } - } - -}; - -template -const std::vector > > IterEquationGroup::EMPTYVECTORSETSS; - -template -const std::vector > IterEquationGroup::EMPTYVECTORSETS; - -template -const std::map > IterEquationGroup::EMPTYMAPSETS; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/patterns/loop.hpp b/ct_core/include/ct/external/cppad/cg/patterns/loop.hpp deleted file mode 100644 index 2d0204cbf..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/loop.hpp +++ /dev/null @@ -1,1221 +0,0 @@ -#ifndef CPPAD_CG_LOOP_INCLUDED -#define CPPAD_CG_LOOP_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -class IndependentOrder { -public: - // provides an independent variable for each loop iteration - const std::vector*> order; - - inline IndependentOrder(const std::vector*>& myOrder) : - order(myOrder) { - } -}; - -template -class OperationArgumentsIndepOrder { -public: - std::map*> arg2Order; -}; - -/** - * - */ -template -class LoopCodeHandler : public CodeHandler { -public: - using CodeHandler::manageOperationNode; - -}; - -/** - * A for loop. - */ -template -class Loop { -private: - typedef std::pair > IndexValue; -public: - /** - * The equations inside the loop - */ - std::set*> equations; - /** - * Which argument positions of operations (from the reference dependent) - * use indexed independent variables - * (operation -> argument index -> iteration -> independent) - */ - IndexedIndependent indexedOpIndep; -private: - /** - * Code handler used to generate the original operation graph - */ - CodeHandler* handlerOrig_; - /** - * - */ - std::unique_ptr> varId_; - /** - * Which variables depend on indexed independents - */ - std::unique_ptr> varIndexed_; - /** - * The number of iterations this loop will have - */ - size_t iterationCount_; - /** - * Code handler for the operations in the loop - */ - LoopCodeHandler handler_; - /** - * Groups of equations which share common temporary variables - */ - std::vector > eqGroups_; - /** - * The order of equation patterns in the loop's tape - */ - std::map*, size_t> equationOrder_; - /** - * The evaluated dependents in each loop iteration - * ([iteration 1]{dep1, dep3, ...}; [iteration 2]{dep5, dep6, ...}; ...) - */ - std::vector > iterationDependents_; - /** - * Map each dependent to its corresponding iteration - */ - std::map dep2Iteration_; - /** - * total number of independent variables in the loop's tape - */ - size_t nIndependents_; - /** - * - */ - LoopModel* loopModel_; - /** - * indexed independent variables for the loop (clones) - */ - std::map*, IndexValue> independentsIndexed_; - /** - * non-indexed independent variables for the loop (clones) - */ - std::map*, IndexValue> independentsNonIndexed_; - /** - * independent variables for the loop created from temporary variables (clones) - */ - std::map*, IndexValue> independentsTemp_; - /** - * id -> clone - */ - std::map*> clonesTemporary_; - /** - * orig -> clone - */ - std::map*, OperationNode*> temporaryClone2Orig_; - /** - * orig -> clone - */ - std::map*, OperationNode*> orig2ConstIndepClone_; - /** - * independent order -> clone - */ - std::map*, OperationNode*> indexedIndep2clone_; - /** - * Maps the independent from the first loop iteration to its independent - * variable order - * (first independent in the order -> all possible orders) - */ - std::map*, std::vector*> > firstIndep2orders_; - /** - * Maps an operations to their arguments and the corresponding - * independent variable order - */ - std::map*, OperationArgumentsIndepOrder* > op2Arg2IndepOrder_; - /** - * used just to keep pointers so that the objects can be deleted later - */ - std::forward_list*> arg2IndepOrder_; - /** - * Variable id counter - */ - size_t idCounter_; -public: - - inline Loop(EquationPattern& eq) : - handlerOrig_(eq.depRef.getCodeHandler()), - varId_(handlerOrig_ != nullptr ? new CodeHandlerVector(*handlerOrig_): nullptr), - varIndexed_(handlerOrig_ != nullptr ? new CodeHandlerVector(*handlerOrig_): nullptr), - iterationCount_(0), // not known yet (only after all equations have been added) - eqGroups_(1), - nIndependents_(0), - loopModel_(nullptr), - idCounter_(0) { // not really required (but it avoids warnings) - //indexedOpIndep(eq.indexedOpIndep), // must be determined later for a different reference - //constOperationIndependents(eq.constOperationIndependents) { - equations.insert(&eq); - eqGroups_[0].equations.insert(&eq); - - if(varId_ != nullptr) - varId_->adjustSize(); - } - - Loop(const Loop& other) = delete; - Loop& operator=(const Loop& rhs) = delete; - - inline void addEquation(EquationPattern& eq) { - equations.insert(&eq); - eqGroups_[0].equations.insert(&eq); - } - - inline void setLinkedDependents(const std::set*>& newLoopRelations) { - CPPADCG_ASSERT_UNKNOWN(eqGroups_.size() == 1); - - eqGroups_[0].linkedDependents.clear(); - eqGroups_[0].linkedDependents.reserve(newLoopRelations.size()); - - for (std::set* it : newLoopRelations) - eqGroups_[0].linkedDependents.push_back(*it); - } - - inline void addLinkedEquationsByNonIndexed(EquationPattern* eq1, - EquationPattern* eq2) { - eqGroups_[0].addLinkedEquationsByNonIndexed(eq1, eq2); - } - - inline size_t getLinkedEquationsByNonIndexedCount() const { - return eqGroups_[0].getLinkedEquationsByNonIndexedCount(); - } - - /** - * The number of iterations this loop will have - */ - inline size_t getIterationCount() const { - return iterationCount_; - } - - const std::vector >& getIterationDependents() const { - return iterationDependents_; - } - - inline LoopModel* getModel() const { - return loopModel_; - } - - inline LoopModel* releaseLoopModel() { - LoopModel* loopAtomic = loopModel_; - loopModel_ = nullptr; - return loopAtomic; - } - - /** - * Combines the provided loop with the current one - * - * @param other The other loop - */ - void merge(Loop& other, - const std::set*>& indexedLoopRelations, - const std::vector*, EquationPattern*> >& nonIndexedLoopRelations) { - CPPADCG_ASSERT_UNKNOWN(iterationCount_ == other.iterationCount_); - - - equations.insert(other.equations.begin(), other.equations.end()); - other.equations.clear(); // so that it does not delete the equations - - CPPADCG_ASSERT_UNKNOWN(eqGroups_.size() == 1); - CPPADCG_ASSERT_UNKNOWN(other.eqGroups_.size() == 1); - - EquationGroup& g = eqGroups_[0]; - EquationGroup& og = other.eqGroups_[0]; - g.equations.insert(og.equations.begin(), og.equations.end()); - - CPPADCG_ASSERT_UNKNOWN(equationOrder_.empty()); - CPPADCG_ASSERT_UNKNOWN(iterationDependents_.empty()); - - g.linkedEquationsByNonIndexed.insert(og.linkedEquationsByNonIndexed.begin(), og.linkedEquationsByNonIndexed.end()); - for (EquationPattern* itNIndexed : indexedLoopRelations) { - g.linkedEquationsByNonIndexed.erase(itNIndexed); - } - - for (size_t e = 0; e < nonIndexedLoopRelations.size(); e++) { - g.addLinkedEquationsByNonIndexed(nonIndexedLoopRelations[e].first, nonIndexedLoopRelations[e].second); - } - - } - - void mergeEqGroups(Loop& other) { - eqGroups_.insert(eqGroups_.end(), other.eqGroups_.begin(), other.eqGroups_.end()); - - size_t nEq = equations.size(); - equations.insert(other.equations.begin(), other.equations.end()); - other.equations.clear(); // so that it does not delete the equations - - /** - * Update equation index - */ - for (const auto& it : other.equationOrder_) { - equationOrder_[it.first] = it.second + nEq; - } - - CPPADCG_ASSERT_UNKNOWN(iterationDependents_.size() == other.iterationDependents_.size()); - for (size_t iter = 0; iter < iterationDependents_.size(); iter++) { - iterationDependents_[iter].insert(other.iterationDependents_[iter].begin(), other.iterationDependents_[iter].end()); - } - - } - - void createLoopModel(const std::vector >& dependents, - const std::vector >& independents, - const std::map*>& dep2Equation, - std::map*, size_t>& origTemp2Index) { - - CPPADCG_ASSERT_UNKNOWN(dep2Iteration_.empty()); - for (size_t iter = 0; iter < iterationCount_; iter++) { - const std::set& deps = iterationDependents_[iter]; - - for (size_t d : deps) { - dep2Iteration_[d] = iter; - } - } - - if(varIndexed_ != nullptr) { - varIndexed_->adjustSize(); - varIndexed_->fill(false); - } - - /** - * Determine the reference iteration for each - */ - for (size_t g = 0; g < eqGroups_.size(); g++) { - eqGroups_[g].findReferenceIteration(); -#ifdef CPPADCG_PRINT_DEBUG - std::cout << "reference iteration=" << eqGroups_[g].refIteration << "\n"; - print(eqGroups_[g].iterationDependents); - std::cout << std::endl; - - typename std::set*>::const_iterator iteq; - for (iteq = eqGroups_[g].equations.begin(); iteq != eqGroups_[g].equations.end(); ++iteq) { - std::cout << "eq dependents="; - print((*iteq)->dependents); - std::cout << std::endl; - } -#endif - } - - - for (size_t g = 0; g < eqGroups_.size(); g++) { - const EquationGroup& group = eqGroups_[g]; - const std::set& refItDep = group.iterationDependents[group.refIteration]; - CPPADCG_ASSERT_UNKNOWN(refItDep.size() == group.equations.size()); - - for (size_t dep : refItDep) { - EquationPattern::uncolor(dependents[dep].getOperationNode(), *varIndexed_); - } - - for (size_t dep : refItDep) { - EquationPattern* eq = dep2Equation.at(dep); - - // operations that use indexed independent variables in the reference iteration - std::set*> indexedOperations; - - eq->findIndexedPath(dep, dependents, *varIndexed_, indexedOperations); - if (dep == eq->depRefIndex) { - for (const auto& itop2a : eq->indexedOpIndep.op2Arguments) { - // currently there is no way to make a distinction between yi = xi and y_(i+1) = x_(i+1) - // since both operations which use indexed independents would be nullptr (the dependent) - // an alias is used for these cases - CPPADCG_ASSERT_UNKNOWN(itop2a.first != nullptr); - addOperationArguments2Loop(itop2a.first, itop2a.second); - } - - } else { - // generate loop references - for (const OperationNode* opLoopRef : indexedOperations) { - // currently there is no way to make a distinction between yi = xi and y_(i+1) = x_(i+1) - // since both operations which use indexed independents would be nullptr (the dependent) - // an alias is used for these cases - CPPADCG_ASSERT_UNKNOWN(opLoopRef != nullptr); - - const OperationNode* opEqRef = eq->operationEO2Reference.at(dep).at(opLoopRef); - addOperationArguments2Loop(opLoopRef, eq->indexedOpIndep.op2Arguments.at(opEqRef)); - } - } - - // not needed anymore (lets free this memory now) - eq->indexedOpIndep.op2Arguments.clear(); - } - } - - /** - * independent variable index patterns - */ - generateIndependentLoopIndexes(); - - if(varId_ != nullptr) - varId_->fill(0); - - createLoopTapeNModel(dependents, independents, dep2Equation, origTemp2Index); - - /** - * Clean-up - */ - if(varId_ != nullptr) - varId_->fill(0); - } - - void generateDependentLoopIndexes(const std::map*>& dep2Equation) { - using namespace std; - - iterationDependents_.clear(); - equationOrder_.clear(); - iterationCount_ = 0; - size_t nMaxIt = 0; - /** - * assign a dependent variable from each equation to an iteration - */ - map*, set > depsInEq; - - for (EquationPattern* eq : equations) { - depsInEq[eq] = eq->dependents; - nMaxIt = std::max(nMaxIt, eq->dependents.size()); - } - - iterationDependents_.reserve(nMaxIt + 2 * equations.size()); - - for (size_t g = 0; g < eqGroups_.size(); g++) { - EquationGroup& group = eqGroups_[g]; - const set*>& eqs = group.equations; - const std::vector >& linkedDependents = group.linkedDependents; - std::vector >& relatedEqIterationDeps = group.iterationDependents; - - relatedEqIterationDeps.reserve(iterationDependents_.size()); - - // assign an index to each equation - for (EquationPattern* eq : eqs) { - size_t eqo_size = equationOrder_.size(); - equationOrder_[eq] = eqo_size; - } - - // sort dependents - set dependents; - for (EquationPattern* eq : eqs) { - dependents.insert(eq->dependents.begin(), eq->dependents.end()); - } - - map*, set > > nIndexedGroupPos2Eq2deps; - - - map*, std::vector > freeDependents; // ordered dependents not assign to any iteration - for (EquationPattern* eq : equations) { - freeDependents[eq].assign(eq->dependents.begin(), eq->dependents.end()); - } - - DependentIndexSorter depSorter(group, freeDependents, dep2Equation); - - set::const_iterator itDep = dependents.begin(); - size_t i = 0; // iteration counter - while (itDep != dependents.end()) { - size_t dep = *itDep; - itDep++; - - if (iterationDependents_.size() <= i) - iterationDependents_.resize(i + 1); - set& itDepi = iterationDependents_[i]; - - if (relatedEqIterationDeps.size() <= i) - relatedEqIterationDeps.resize(i + 1); - set& ritDepi = relatedEqIterationDeps[i]; - - // this dependent might not be the best dependent if this equation is not present in all iterations - - EquationPattern* eq = dep2Equation.at(dep); - auto bestDep = depSorter.findBestDependentForIteration(dep, eq); - dep = bestDep.first; - eq = bestDep.second; - - long pos = group.findIndexedLinkedDependent(dep); - if (pos >= 0) { - // assign the dependent to the first iteration with all its relationships - for (size_t dep2 : linkedDependents[pos]) { - if (dep2 == *itDep) itDep++; //make sure the iterator is valid - itDepi.insert(dep2); - ritDepi.insert(dep2); - dependents.erase(dep2); - - EquationPattern* eq2 = dep2Equation.at(dep2); - std::vector& eq2FreeDep = freeDependents[eq2]; - typename std::vector::iterator itFreeDep2; - itFreeDep2 = std::find(eq2FreeDep.begin(), eq2FreeDep.end(), dep2); // consider using lower_bound instead - CPPADCG_ASSERT_UNKNOWN(itFreeDep2 != eq2FreeDep.end()); - - eq2FreeDep.erase(itFreeDep2); - } - - i++; - } else { - // maybe this dependent shares a non-indexed temporary variable - long posN = group.findNonIndexedLinkedRel(eq); - if (posN >= 0) { - // there are only non-indexed shared relations with other equations (delay processing...) - dependents.erase(dep); // safe because of itDep++ - nIndexedGroupPos2Eq2deps[posN][eq].insert(dep); - } else { - itDepi.insert(dep); - ritDepi.insert(dep); - - std::vector& eqFreeDep = freeDependents[eq]; - auto itFreeDep = find(eqFreeDep.begin(), eqFreeDep.end(), dep); // consider using lower_bound instead - CPPADCG_ASSERT_UNKNOWN(itFreeDep != eqFreeDep.end()); - - eqFreeDep.erase(itFreeDep); - - i++; - } - } - - } - - /** - * place dependents which only share non-indexed variables - */ - if (!nIndexedGroupPos2Eq2deps.empty()) { - - map*, set > eqIterations; - for (size_t i = 0; i < relatedEqIterationDeps.size(); i++) { - const set& deps = relatedEqIterationDeps[i]; - for (size_t dep : deps) { - eqIterations[dep2Equation.at(dep)].insert(i); - } - } - - for (auto& itPos2Eq2Dep : nIndexedGroupPos2Eq2deps) { - size_t posN = itPos2Eq2Dep.first; - // must pick one dependent from each equation for each iteration - std::vector deps; - deps.reserve(itPos2Eq2Dep.second.size()); - - set usedIterations; // iterations used by these equations - // determine used iteration indexes - const set*>& relations = group.linkedEquationsByNonIndexedRel[posN]; - for (EquationPattern* itRel : relations) { - const set& iters = eqIterations[itRel]; - usedIterations.insert(iters.begin(), iters.end()); - } - - while (true) { - - // must pick one dependent from each equation for each iteration - deps.clear(); - - for (auto& itEq2Dep : itPos2Eq2Dep.second) { - if (!itEq2Dep.second.empty()) { - deps.push_back(*itEq2Dep.second.begin()); - itEq2Dep.second.erase(itEq2Dep.second.begin()); - } - } - - if (deps.empty()) { - break; // done - } - - // find a free iteration index - size_t i = 0; - set::const_iterator itIter; - for (itIter = usedIterations.begin(); itIter != usedIterations.end();) { - size_t i1 = *itIter; - ++itIter; - if (itIter != usedIterations.end()) { - size_t i2 = *itIter; - if (i2 - i1 != 1) { - i = i1 + 1; - break; - } - } else { - i = i1 + 1; - } - } - - // add the dependents to the iteration - usedIterations.insert(i); - - if (iterationDependents_.size() <= i) - iterationDependents_.resize(i + 1); - set& itDepi = iterationDependents_[i]; - - if (relatedEqIterationDeps.size() <= i) - relatedEqIterationDeps.resize(i + 1); - set& ritDepi = relatedEqIterationDeps[i]; - itDepi.insert(deps.begin(), deps.end()); - ritDepi.insert(deps.begin(), deps.end()); - } - } - /** - * @todo reorder iterations according to the lowest - * dependent in each iteration if there were new - * iterations only with dependents related by - * non-indexed shared variables - */ - - } - - iterationCount_ = std::max(iterationCount_, iterationDependents_.size()); - } - - } - - /** - * Destructor - */ - virtual ~Loop() { - for (const auto& itf : firstIndep2orders_) { - for (IndependentOrder* ito : itf.second) { - delete ito; - } - } - - for (OperationArgumentsIndepOrder* itio : arg2IndepOrder_) { - delete itio; - } - - for (EquationPattern* eq : equations) { - delete eq; - } - - delete loopModel_; - } - - /*********************************************************************** - * private - **********************************************************************/ -private: - - void addOperationArguments2Loop(const OperationNode* op, - const OperationIndexedIndependents& eqOpIndeIndep) { - CPPADCG_ASSERT_UNKNOWN(!dep2Iteration_.empty()); - - OperationIndexedIndependents& loopOpIndeIndep = indexedOpIndep.op2Arguments[op]; - loopOpIndeIndep.arg2Independents.resize(eqOpIndeIndep.arg2Independents.size()); - - // some iterations might have not been defined by previous equation patterns - for (size_t a = 0; a < eqOpIndeIndep.arg2Independents.size(); a++) { - if (eqOpIndeIndep.arg2Independents[a].empty()) - continue; - - for (const auto& itDepIndep : eqOpIndeIndep.arg2Independents[a]) { - size_t dep = itDepIndep.first; - size_t iter = dep2Iteration_.at(dep); - loopOpIndeIndep.arg2Independents[a][iter] = itDepIndep.second; - } - } - - } - - void generateIndependentLoopIndexes() { - CPPADCG_ASSERT_UNKNOWN(iterationCount_ > 0); //number of iterations and dependent indexes must have already been determined - - // loop all operations from the reference dependents which use indexed independents - for (const auto& it : indexedOpIndep.op2Arguments) { - const OperationNode* operation = it.first; - const OperationIndexedIndependents& opInd = it.second; - - OperationArgumentsIndepOrder* arg2orderPos = new OperationArgumentsIndepOrder(); - op2Arg2IndepOrder_[operation] = arg2orderPos; - - arg2IndepOrder_.push_front(arg2orderPos); - - // loop all arguments - size_t aSize = opInd.arg2Independents.size(); - for (size_t argumentIndex = 0; argumentIndex < aSize; argumentIndex++) { - const std::map*>& dep2Indep = opInd.arg2Independents[argumentIndex]; - if (dep2Indep.empty()) - continue; // not an indexed variable - - std::vector*> order(iterationCount_); - - /** - * create the independent variable order - */ - CPPADCG_ASSERT_UNKNOWN(dep2Indep.size() > 0 && dep2Indep.size() <= iterationCount_); - for (const auto& itDep2Indep : dep2Indep) { - size_t iterationIndex = itDep2Indep.first; - const OperationNode* indep = itDep2Indep.second; - - order[iterationIndex] = indep; - } - - /** - * try to find an existing independent variable order - */ - std::vector*>& availableOrders = firstIndep2orders_[order[0]]; - IndependentOrder* match = nullptr; - - long a_size = availableOrders.size(); - for (long o = 0; o < a_size; o++) { - IndependentOrder* orderO = availableOrders[o]; - bool ok = true; - for (size_t iterationIndex = 0; iterationIndex < iterationCount_; iterationIndex++) { - if (orderO->order[iterationIndex] != order[iterationIndex]) { - ok = false; - break; - } - } - if (ok) { - match = orderO; - break; - } - } - - if (match != nullptr) { - // found another operation with the same independent variable order - arg2orderPos->arg2Order[argumentIndex] = match; - } else { - // brand new independent variable order - IndependentOrder* iOrder = new IndependentOrder(order); - availableOrders.push_back(iOrder); - arg2orderPos->arg2Order[argumentIndex] = iOrder; - } - - } - - } - } - - /** - * Creates the model for the loop equations - * - * @param dependents original model dependent variable vector - * @param independents original model independent variable vector - * @param dep2Equation maps an equation/dependent index to an equation pattern - * @param origTemp2Index - */ - void createLoopTapeNModel(const std::vector >& dependents, - const std::vector >& independents, - const std::map*>& dep2Equation, - std::map*, size_t>& origTemp2Index) { - typedef CG CGB; - typedef AD ADCGB; - CPPADCG_ASSERT_UNKNOWN(independents.size() > 0); - CPPADCG_ASSERT_UNKNOWN(independents[0].getCodeHandler() != nullptr); - CodeHandler& origHandler = *independents[0].getCodeHandler(); - - /** - * create the new/clone operations for the reference iteration only - */ - nIndependents_ = 0; - idCounter_ = 1; - - CPPADCG_ASSERT_UNKNOWN(equationOrder_.size() == equations.size()); - - std::vector deps(equations.size()); - - for (size_t g = 0; g < eqGroups_.size(); g++) { - const EquationGroup& group = eqGroups_[g]; - const std::set& iterationDependents = group.iterationDependents[group.refIteration]; - - for (size_t depIndex : iterationDependents) { - EquationPattern* eq = dep2Equation.at(depIndex); - OperationNode* node = dependents[depIndex].getOperationNode(); - - Argument aClone; - - if (node != nullptr) { - if (node->getOperationType() == CGOpCode::Inv) { - aClone = createIndependentClone(nullptr, 0, *node); - } else { - aClone = makeGraphClones(*eq, *node); - } - } else { - aClone = dependents[depIndex].getValue(); - } - - size_t i = equationOrder_.at(eq); - deps[i] = CGB(aClone); - } - } - - /******************************************************************* - * create the tape for the reference iteration - ******************************************************************/ - // indexed independents - CPPADCG_ASSERT_UNKNOWN(indexedIndep2clone_.size() == independentsIndexed_.size()); - - std::vector*> indexedCloneOrder; - indexedCloneOrder.reserve(indexedIndep2clone_.size()); - - std::map*, const IndependentOrder*> clone2indexedIndep; - for (const auto& it : indexedIndep2clone_) { - clone2indexedIndep[it.second] = it.first; - indexedCloneOrder.push_back(it.second); - } - - struct IndexedIndepSorter indexedSorter(clone2indexedIndep); - std::sort(indexedCloneOrder.begin(), indexedCloneOrder.end(), indexedSorter); - - // original indep index -> non-indexed independent clones - std::map*> nonIndexedCloneOrder; - - // [tape variable] = original independent index - std::map*, const OperationNode*> clones2ConstIndep; - size_t s = 0; - for (auto itc = orig2ConstIndepClone_.begin(); itc != orig2ConstIndepClone_.end(); ++itc, s++) { - const OperationNode* orig = itc->first; - OperationNode* clone = itc->second; - - size_t j = orig->getInfo()[0]; - clones2ConstIndep[clone] = orig; - nonIndexedCloneOrder[j] = clone; - } - - size_t nIndexed = indexedCloneOrder.size(); - size_t nNonIndexed = nonIndexedCloneOrder.size(); - size_t nTmpIndexed = independentsTemp_.size(); - - // tape independent array - size_t nIndep = independentsIndexed_.size() + - independentsNonIndexed_.size() + - independentsTemp_.size(); - std::vector loopIndeps(nIndep); - - typename std::map*, IndexValue>::const_iterator itt; - typename std::map*>::const_iterator origJ2CloneIt; - - if (nIndep == 0) { - loopIndeps.resize(1); // the tape cannot have 0 independents - loopIndeps[0] = Base(0); - - } else { - - /** - * assign values from the original model if possible (to avoid NaN) - */ - for (size_t j = 0; j < nIndexed; j++) { - const IndexValue& iv = independentsIndexed_.at(indexedCloneOrder[j]); - loopIndeps[j] = iv.second; - } - - s = 0; - for (origJ2CloneIt = nonIndexedCloneOrder.begin(); origJ2CloneIt != nonIndexedCloneOrder.end(); ++origJ2CloneIt, s++) { - const IndexValue& iv = independentsNonIndexed_.at(origJ2CloneIt->second); - loopIndeps[nIndexed + s] = iv.second; - } - - s = 0; - for (itt = independentsTemp_.begin(); itt != independentsTemp_.end(); ++itt, s++) { - const IndexValue& iv = itt->second; - loopIndeps[nIndexed + nNonIndexed + s] = iv.second; - } - } - - /** - * register the independent variables - */ - CppAD::Independent(loopIndeps); - - /** - * Reorder independent variables for the new tape (reference iteration only) - */ - std::vector localIndeps(nIndep); - if (nIndep > 0) { - for (size_t j = 0; j < nIndexed; j++) { - const IndexValue& iv = independentsIndexed_.at(indexedCloneOrder[j]); - size_t localIndex = iv.first; - localIndeps[localIndex] = loopIndeps[j]; - } - - s = 0; - for (origJ2CloneIt = nonIndexedCloneOrder.begin(); origJ2CloneIt != nonIndexedCloneOrder.end(); ++origJ2CloneIt, s++) { - size_t localIndex = independentsNonIndexed_.at(origJ2CloneIt->second).first; - localIndeps[localIndex] = loopIndeps[nIndexed + s]; - } - - s = 0; - for (itt = independentsTemp_.begin(); itt != independentsTemp_.end(); ++itt, s++) { - size_t localIndex = itt->second.first; - localIndeps[localIndex] = loopIndeps[nIndexed + nNonIndexed + s]; - } - } - - /** - * create the tape - */ - Evaluator evaluator1stIt(handler_); - - // load any atomic function used in the original model - const std::map* >& atomicsOrig = origHandler.getAtomicFunctions(); - std::map* > atomics; - atomics.insert(atomicsOrig.begin(), atomicsOrig.end()); - evaluator1stIt.addAtomicFunctions(atomics); - - std::vector newDeps = evaluator1stIt.evaluate(localIndeps, deps); - - std::unique_ptr >funIndexed(new ADFun()); - funIndexed->Dependent(newDeps); - - /******************************************************************* - * create the loop model object - ******************************************************************/ - std::vector > dependentOrigIndexes(equations.size(), std::vector (iterationCount_, std::numeric_limits::max())); - for (size_t it = 0; it < iterationCount_; it++) { - const std::set& itDeps = iterationDependents_[it]; - for (size_t origDep : itDeps) { - EquationPattern* eq = dep2Equation.at(origDep); - size_t i = equationOrder_.at(eq); - dependentOrigIndexes[i][it] = origDep; - } - } - - //[tape variable][iteration] = original independent index - std::vector > indexedIndependents(nIndexed, std::vector(iterationCount_)); - for (size_t j = 0; j < indexedCloneOrder.size(); j++) { - const IndependentOrder* origOrder = clone2indexedIndep.at(indexedCloneOrder[j]); - for (size_t it = 0; it < iterationCount_; it++) { - const OperationNode* indep = origOrder->order[it]; - size_t index; - if (indep != nullptr) { - index = indep->getInfo()[0]; - } else { - index = std::numeric_limits::max(); // not used at this iteration by any equation - } - indexedIndependents[j][it] = index; - } - } - - std::vector temporaryIndependents(nTmpIndexed); - - size_t j = 0; - for (itt = independentsTemp_.begin(); itt != independentsTemp_.end(); ++itt, j++) { - const OperationNode* tmpClone = itt->first; - OperationNode* origTmpNode = temporaryClone2Orig_.at(tmpClone); - - /** - * assign an index (k) to each temporary variable - */ - size_t k; - typename std::map*, size_t>::const_iterator itz = origTemp2Index.find(origTmpNode); - if (itz == origTemp2Index.end()) { - k = origTemp2Index.size(); - origTemp2Index[origTmpNode] = k; // new index for a temporary variable - } else { - k = itz->second; - } - - temporaryIndependents[j] = k; - } - - std::vector nonIndexedIndependents(orig2ConstIndepClone_.size()); - s = 0; - for (origJ2CloneIt = nonIndexedCloneOrder.begin(); origJ2CloneIt != nonIndexedCloneOrder.end(); ++origJ2CloneIt, s++) { - nonIndexedIndependents[s] = origJ2CloneIt->first; - } - - loopModel_ = new LoopModel(funIndexed.release(), - iterationCount_, - dependentOrigIndexes, - indexedIndependents, - nonIndexedIndependents, - temporaryIndependents); - - loopModel_->detectIndexPatterns(); - } - - inline Argument makeGraphClones(const EquationPattern& eq, - OperationNode& node) { - - CPPADCG_ASSERT_UNKNOWN(node.getOperationType() != CGOpCode::Inv); - - size_t id = (*varId_)[node]; - - if (id > 0) { - // been here before - return Argument(*clonesTemporary_.at(id)); - } - - //handler_.markVisited(node); - - id = idCounter_++; - (*varId_)[node] = id; - - if ((*varIndexed_)[node] || node.getOperationType() == CGOpCode::ArrayCreation) { - /** - * part of the operation path that depends on the loop indexes - * or its an array with constant elements - */ - const std::vector >& args = node.getArguments(); - size_t arg_size = args.size(); - std::vector > cloneArgs(arg_size); - - for (size_t a = 0; a < arg_size; a++) { - OperationNode* argOp = args[a].getOperation(); - if (argOp == nullptr) { - // parameter - cloneArgs[a] = *args[a].getParameter(); - } else { - // variable - if (argOp->getOperationType() == CGOpCode::Inv) { - cloneArgs[a] = createIndependentClone(&node, a, *argOp); - } else { - cloneArgs[a] = makeGraphClones(eq, *argOp); - } - } - } - - OperationNode* cloneOp = handler_.makeNode(node.getOperationType(), - node.getInfo(), - cloneArgs); - - clonesTemporary_[id] = cloneOp; - return Argument(*cloneOp); - - } else { - /** - * temporary variable used in all iterations - * (does not depend on indexes) - */ - return makeTemporaryVarClone(node); - } - } - - inline OperationNode& createIndependentClone(OperationNode* operation, - size_t argumentIndex, - OperationNode& independent) { - - // is it an indexed independent? - typename std::map*, OperationIndexedIndependents >::const_iterator it = indexedOpIndep.op2Arguments.find(operation); - if (it != indexedOpIndep.op2Arguments.end()) { - const OperationIndexedIndependents& yyy = it->second; - - if (!yyy.arg2Independents[argumentIndex].empty()) { - // yes - return getIndexedIndependentClone(operation, argumentIndex); - } - } - - // it is constant for all operation - return getNonIndexedIndependentClone(independent); - } - - OperationNode& getIndexedIndependentClone(const OperationNode* operation, - size_t argIndex) { - CPPADCG_ASSERT_UNKNOWN(operation == nullptr || operation->getArguments().size() > argIndex); - CPPADCG_ASSERT_UNKNOWN(operation == nullptr || operation->getArguments()[argIndex].getOperation() != nullptr); - CPPADCG_ASSERT_UNKNOWN(operation == nullptr || operation->getArguments()[argIndex].getOperation()->getOperationType() == CGOpCode::Inv); - - OperationArgumentsIndepOrder* args2Order = op2Arg2IndepOrder_.at(operation); - IndependentOrder* indepOrder = args2Order->arg2Order.at(argIndex); - - typename std::map*, OperationNode*>::const_iterator it; - it = indexedIndep2clone_.find(indepOrder); - if (it != indexedIndep2clone_.end()) { - return *it->second; - } else { - CG newIndep; - handler_.makeVariable(newIndep); - independentsIndexed_[newIndep.getOperationNode()] = IndexValue(nIndependents_, newIndep); - nIndependents_++; - - OperationNode* clone = newIndep.getOperationNode(); - indexedIndep2clone_[indepOrder] = clone; - return *clone; - } - } - - OperationNode& getNonIndexedIndependentClone(const OperationNode& node) { - CPPADCG_ASSERT_UNKNOWN(node.getOperationType() == CGOpCode::Inv); - - typename std::map*, OperationNode*>::iterator it; - it = orig2ConstIndepClone_.find(&node); - if (it != orig2ConstIndepClone_.end()) { - return *it->second; - } - - CG newIndep; - handler_.makeVariable(newIndep); - independentsNonIndexed_[newIndep.getOperationNode()] = IndexValue(nIndependents_, newIndep); - nIndependents_++; - - OperationNode* clone = newIndep.getOperationNode(); - orig2ConstIndepClone_[&node] = clone; - return *clone; - } - - /** - * Creates a temporary variable that does NOT depend on the loop indexes - * - * @param node The original node - * @return the clone - */ - OperationNode& makeTemporaryVarClone(OperationNode& node) { - CPPADCG_ASSERT_UNKNOWN(node.getOperationType() != CGOpCode::Inv); - CPPADCG_ASSERT_UNKNOWN(node.getOperationType() != CGOpCode::ArrayCreation); - CPPADCG_ASSERT_UNKNOWN(node.getOperationType() != CGOpCode::SparseArrayCreation); - - CG newIndep; - handler_.makeVariable(newIndep); - OperationNode* cloneOp = newIndep.getOperationNode(); - - temporaryClone2Orig_[cloneOp] = &node; - independentsTemp_[cloneOp] = IndexValue(nIndependents_, newIndep); - nIndependents_++; - - size_t id = idCounter_++; - clonesTemporary_[id] = cloneOp; - (*varId_)[node] = id; - - return *cloneOp; - } - - /** - * Class used to help assign dependent variables to iterations - */ - class DependentIndexSorter { - private: - const EquationGroup& group; - const std::map*, std::vector >& freeDependents; - const std::map*>& dep2Equation; - std::set*> visitedEq; - public: - - inline DependentIndexSorter(const EquationGroup& g, - const std::map*, std::vector >& f, - const std::map*>& d2e) : - group(g), - freeDependents(f), - dep2Equation(d2e) { - } - - /** - * Tries to find the best dependent to use for the next iteration. - * For performance reasons it might not be the optimum. - * - * @param dep The dependent index - * @param eq The equation - * @return the best dependent index and its equation - */ - inline std::pair*> findBestDependentForIteration(size_t dep, EquationPattern* eq) { - visitedEq.clear(); - return findBestDependent(dep, eq); - } - - private: - - inline size_t findRelativeFreeDependentInEq(EquationPattern* eq, size_t dep) { - // find relative order of the dependent in the equation - const std::vector& eqFreeDep = freeDependents.at(eq); - for (size_t depRelPos = 0; depRelPos < eqFreeDep.size(); depRelPos++) {// consider using lower_bound - if (eqFreeDep[depRelPos] == dep) - return depRelPos; // found it - } - - assert(false); - return eqFreeDep.size(); // should not happen - } - - /** - * Tries to find the best dependent to use for the next iteration - * - * @param dep The dependent index - * @param eq The equation - * @return the best dependent index and its equation - */ - inline std::pair*> findBestDependent(size_t dep, EquationPattern* eq) { - visitedEq.insert(eq); - - auto best = std::make_pair(dep, eq); - - // find the group of dependents in the same iteration (associated by indexed independents) - long pos = group.findIndexedLinkedDependent(dep); - if (pos >= 0) { - size_t depRelPos = findRelativeFreeDependentInEq(eq, dep); - - // this dependent might not be the best dependent if this - // equation is not present in all iterations - for (size_t dep2 : group.linkedDependents[pos]) { - EquationPattern* eq2 = dep2Equation.at(dep2); - if (visitedEq.find(eq2) != visitedEq.end()) continue; - - size_t dep2RelPos = findRelativeFreeDependentInEq(eq2, dep2); - if (dep2RelPos > depRelPos) { - // this equation has more dependents before - // one these other dependents would be better - best = std::make_pair(dep2, eq2); - depRelPos = dep2RelPos; - } - } - - if (best.first != dep) { - size_t bestDep = *freeDependents.at(best.second).begin(); - return findBestDependent(bestDep, best.second); - } - - } - - return best; - } - - }; - - /** - * structure used to sort the loop's indexed independent variables - */ - struct IndexedIndepSorter { - const std::map*, const IndependentOrder*>& clone2indexedIndep; - - IndexedIndepSorter(const std::map*, const IndependentOrder*>& clone2indexedIndep_) : - clone2indexedIndep(clone2indexedIndep_) { - } - - bool operator()(const OperationNode* node1, - const OperationNode* node2) { - const IndependentOrder* indepOrder1 = clone2indexedIndep.at(node1); - const IndependentOrder* indepOrder2 = clone2indexedIndep.at(node2); - CPPADCG_ASSERT_UNKNOWN(indepOrder1->order.size() == indepOrder2->order.size()); - - size_t size = indepOrder1->order.size(); - for (size_t j = 0; j < size; j++) { - const OperationNode* indep1 = indepOrder1->order[j]; - const OperationNode* indep2 = indepOrder2->order[j]; - // some variables are not used in all iterations - if (indep1 == nullptr) { - if (indep2 == nullptr) { - continue; - } - return false; - } else if (indep2 == nullptr) { - return true; - } - - size_t index1 = indep1->getInfo()[0]; - size_t index2 = indep2->getInfo()[0]; - if (index1 < index2) - return true; - else if (index1 > index2) - return false; - } - - CPPADCG_ASSERT_UNKNOWN(false); // should never get here - return false; - } - }; - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif diff --git a/ct_core/include/ct/external/cppad/cg/patterns/loop_free_model.hpp b/ct_core/include/ct/external/cppad/cg/patterns/loop_free_model.hpp deleted file mode 100644 index ba6f07735..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/loop_free_model.hpp +++ /dev/null @@ -1,400 +0,0 @@ -#ifndef CPPAD_CG_LOOP_FREE_MODEL_INCLUDED -#define CPPAD_CG_LOOP_FREE_MODEL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Altered model without the loop equations and with extra dependents - * for the non-indexed temporary variables used by loops - * - * @author Joao Leal - */ -template -class LoopFreeModel { -public: - typedef CppAD::cg::CG CGB; - typedef Argument Arg; - typedef std::vector > VectorSet; -protected: - /** - * The tape - */ - ADFun * const fun_; - /** - * The dependent variables in this tape to their original indexes - */ - std::vector dependentIndexes_; - std::map dependentOrig2Local; - /** - * Jacobian sparsity pattern of the tape - */ - VectorSet jacTapeSparsity_; - bool jacSparsity_; - /** - * Hessian sparsity pattern for equations used to determine the - * temporaries (ignores the the original model equations) - */ - VectorSet hessTapeTempSparsity_; - /** - * Hessian sparsity pattern for the original model equations in the tape - * (ignores the equations for the temporaries) - */ - VectorSet hessTapeOrigEqSparsity_; - // whether or not the hessian sparsities have been evaluated - bool hessSparsity_; -public: - - /** - * Creates a model for the non-indexed operations - * - * @param fun - * @param dependentOrigIndexes - */ - LoopFreeModel(ADFun* fun, - const std::vector& dependentOrigIndexes) : - fun_(fun), - dependentIndexes_(dependentOrigIndexes), - jacSparsity_(false), - hessSparsity_(false) { - CPPADCG_ASSERT_KNOWN(fun != nullptr, "fun cannot be null"); - CPPADCG_ASSERT_KNOWN(dependentOrigIndexes.size() <= fun->Range(), "invalid size"); - - for (size_t il = 0; il < dependentIndexes_.size(); il++) - dependentOrig2Local[dependentIndexes_[il]] = il; - } - - LoopFreeModel(const LoopFreeModel&) = delete; - LoopFreeModel& operator=(const LoopFreeModel&) = delete; - - inline ADFun& getTape() const { - return *fun_; - } - - inline size_t getTapeDependentCount() const { - return fun_->Range(); - } - - inline size_t getTemporaryDependentCount() const { - return fun_->Range() - dependentIndexes_.size(); - } - - inline size_t getTapeIndependentCount() const { - return fun_->Domain(); - } - - /** - * Provides the dependent variables indexes present in the original - * model - */ - inline const std::vector& getOrigDependentIndexes() const { - return dependentIndexes_; - } - - inline size_t getLocalDependentIndex(size_t origI) const { - return dependentOrig2Local.at(origI); - } - - inline void evalJacobianSparsity() { - if (!jacSparsity_) { - jacTapeSparsity_ = jacobianSparsitySet(*fun_); - jacSparsity_ = true; - } - } - - inline const VectorSet& getJacobianSparsity() const { - return jacTapeSparsity_; - } - - inline void evalHessianSparsity() { - if (!hessSparsity_) { - size_t mo = dependentIndexes_.size(); - size_t m = fun_->Range(); - size_t n = fun_->Domain(); - - // hessian for the original equations - std::set eqs; - if (mo != 0) { - for (size_t i = 0; i < mo; i++) - eqs.insert(eqs.end(), i); - - hessTapeOrigEqSparsity_ = hessianSparsitySet >, CGB>(*fun_, eqs); - } - - // hessian for the temporary variable equations - if (m != mo) { - eqs.clear(); - for (size_t i = mo; i < m; i++) - eqs.insert(eqs.end(), i); - hessTapeTempSparsity_ = hessianSparsitySet >, CGB>(*fun_, eqs); - } else { - hessTapeTempSparsity_.resize(n); - } - - hessSparsity_ = true; - } - } - - inline const VectorSet& getHessianTempEqsSparsity() const { - CPPADCG_ASSERT_UNKNOWN(hessSparsity_); - return hessTapeTempSparsity_; - } - - inline const VectorSet& getHessianOrigEqsSparsity() const { - CPPADCG_ASSERT_UNKNOWN(hessSparsity_); - return hessTapeOrigEqSparsity_; - } - - /** - * Creates conditional nodes for temporary variables - * - * @param handler source code handler - * @param iterations the iterations where the value should be evaluated - * @param iterCount the number of iteration of the loop - * @param value the value determined inside the loop - * @param iterationIndexOp the iteration index operation for this loop - * @return - */ - inline CG createConditionalOperation(CodeHandler& handler, - const std::set& iterations, - size_t iterCount, - const CG& value, - IndexOperationNode& iterationIndexOp) { - using namespace std; - - if (iterations.size() == iterCount) { - // present in all iterations - - return value; - - } else { - - // no point in creating branches where both branch sides are zero - if (value.isIdenticalZero()) - return value; - - /** - * must create a conditional element so that this - * contribution is only evaluated at the relevant iterations - */ - OperationNode* tmpDclVar = handler.makeNode(CGOpCode::TmpDcl); - Argument tmpArg(*tmpDclVar); - - set usedIter; - OperationNode* cond = loops::createIndexConditionExpressionOp(handler, iterations, usedIter, iterCount - 1, iterationIndexOp); - - // if - OperationNode* ifStart = handler.makeNode(CGOpCode::StartIf, *cond); - - OperationNode* tmpAssign1 = handler.makeNode(CGOpCode::LoopIndexedTmp,{tmpArg, asArgument(value)}); - OperationNode* ifAssign = handler.makeNode(CGOpCode::CondResult,{*ifStart, *tmpAssign1}); - - // else - OperationNode* elseStart = handler.makeNode(CGOpCode::Else,{*ifStart, *ifAssign}); - - OperationNode* tmpAssign2 = handler.makeNode(CGOpCode::LoopIndexedTmp,{tmpArg, Base(0)}); - OperationNode* elseAssign = handler.makeNode(CGOpCode::CondResult,{*elseStart, *tmpAssign2}); - - // end if - OperationNode* endIf = handler.makeNode(CGOpCode::EndIf,{*elseStart, *elseAssign}); - - // - OperationNode* tmpVar = handler.makeNode(CGOpCode::Tmp,{tmpArg, *endIf}); - return CG(*tmpVar); - } - - } - - /** - * Determines the Hessian for the temporary variables only used by - * each loop - * - * @param loopHessInfo - * @param x the independent variables - * @param temps - * @param noLoopEvalJacSparsity - * @param individualColoring - * @param iterationIndexOp - * @return - */ - inline std::map > calculateJacobianHessianUsedByLoops(CodeHandler& handler, - std::map*, loops::HessianWithLoopsInfo >& loopHessInfo, - const std::vector& x, - std::vector& temps, - const VectorSet& noLoopEvalJacSparsity, - bool individualColoring) { - using namespace std; - using namespace CppAD::cg::loops; - - CPPADCG_ASSERT_UNKNOWN(hessSparsity_); // check that the sparsities have been evaluated - - size_t mo = dependentIndexes_.size(); - size_t m = getTapeDependentCount(); - size_t n = fun_->Domain(); - - std::vector > vwNoLoop(loopHessInfo.size()); - std::vector > > vhessNoLoop(loopHessInfo.size()); - - /** - * Hessian - temporary variables - */ - std::vector > noLoopEvalHessTempsSparsity(n); - - for (const auto& itLoop2Info : loopHessInfo) { - const HessianWithLoopsInfo& info = itLoop2Info.second; - - addMatrixSparsity(info.noLoopEvalHessTempsSparsity, noLoopEvalHessTempsSparsity); - } - std::vector hesRow, hesCol; - generateSparsityIndexes(noLoopEvalHessTempsSparsity, hesRow, hesCol); - - size_t l = 0; - for (const auto& itLoop2Info : loopHessInfo) { - LoopModel* loop = itLoop2Info.first; - const HessianWithLoopsInfo& info = itLoop2Info.second; - - const std::vector >& eqGroups = loop->getEquationsGroups(); - size_t nIterations = loop->getIterationCount(); - size_t nEqGroups = eqGroups.size(); - - std::vector& wNoLoop = vwNoLoop[l]; - wNoLoop.resize(m); - for (size_t inl = 0; inl < mo; inl++) { - wNoLoop[inl] = Base(0); - } - - for (size_t inl = mo; inl < m; inl++) { - size_t k = inl - mo; - const LoopPosition* posK = loop->getTempIndepIndexes(k); - - if (posK != nullptr) { - - for (size_t g = 0; g < nEqGroups; g++) { - const IterEquationGroup& group = eqGroups[g]; - - CGB v = Base(0); - - for (size_t tapeI : group.tapeI) { - const map& row = info.dyiDzk[tapeI]; - typename map::const_iterator itCol = row.find(posK->tape); - if (itCol != row.end()) { - const CGB& dydz = itCol->second; - v += dydz * info.w[tapeI]; - } - } - - /** - * Some equations are not present in all iterations - */ - v = createConditionalOperation(handler, - group.iterations, - nIterations, - v, - *info.iterationIndexOp); - - wNoLoop[inl] += v; - } - - } - } - - l++; - } - - std::vector > dyDx; - generateLoopForJacHes(*fun_, x, vwNoLoop, temps, - getJacobianSparsity(), - noLoopEvalJacSparsity, - dyDx, - hessTapeTempSparsity_, - noLoopEvalHessTempsSparsity, - vhessNoLoop, - individualColoring); - - // save Jacobian - map > dzDx; - for (size_t inl = mo; inl < m; inl++) { - // dz_k/dx_v (for temporary variable) - size_t k = inl - mo; - dzDx[k] = dyDx[inl]; - } - - // save Hessian - l = 0; - for (auto& itLoop2Info : loopHessInfo) { - HessianWithLoopsInfo& info = itLoop2Info.second; - info.dzDxx = vhessNoLoop[l]; - l++; - } - - return dzDx; - } - - inline void calculateHessian4OrignalEquations(const std::vector& x, - const std::vector& w, - const VectorSet& noLoopEvalHessSparsity, - const std::vector > >& noLoopEvalHessLocations, - std::vector& hess) { - using namespace std; - using namespace CppAD::cg::loops; - - CPPADCG_ASSERT_UNKNOWN(hessSparsity_); // check that the sparsities have been evaluated - - std::vector wNoLoop(getTapeDependentCount()); - std::vector hessNoLoop; - - /** - * hessian - original equations - */ - std::vector row, col; - generateSparsityIndexes(noLoopEvalHessSparsity, row, col); - - if (row.size() > 0) { - hessNoLoop.resize(row.size()); - - for (size_t inl = 0; inl < dependentIndexes_.size(); inl++) { - wNoLoop[inl] = w[dependentIndexes_[inl]]; - } - - CppAD::sparse_hessian_work work; // temporary structure for CPPAD - // "cppad.symmetric" may have missing values for functions using - // atomic functions which only provide half of the elements - // (some values could be zeroed) - work.color_method = "cppad.general"; - fun_->SparseHessian(x, wNoLoop, hessTapeOrigEqSparsity_, row, col, hessNoLoop, work); - - // save non-indexed hessian elements - for (size_t el = 0; el < row.size(); el++) { - size_t j1 = row[el]; - size_t j2 = col[el]; - const set& locations = noLoopEvalHessLocations[j1].at(j2); - for (size_t itE : locations) - hess[itE] = hessNoLoop[el]; - } - } - } - - virtual ~LoopFreeModel() { - delete fun_; - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/patterns/loop_model.hpp b/ct_core/include/ct/external/cppad/cg/patterns/loop_model.hpp deleted file mode 100644 index 83816ff48..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/loop_model.hpp +++ /dev/null @@ -1,509 +0,0 @@ -#ifndef CPPAD_CG_LOOP_MODEL_INCLUDED -#define CPPAD_CG_LOOP_MODEL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * An atomic function for source code generation within loops - * - * @author Joao Leal - */ -template -class LoopModel { -public: - typedef CppAD::cg::CG CGB; - typedef Argument Arg; - typedef std::pair pairss; -public: - static const std::string ITERATION_INDEX_NAME; -private: - static const std::set EMPTYSET; -private: - const size_t loopId_; - /** - * The tape for a single loop iteration - */ - ADFun * const fun_; - /** - * Number of loop iterations - */ - const size_t iterationCount_; - /** - * Loop tape dependent variable count (number of equation patterns) - */ - const size_t m_; - /** - * The dependent variables ([tape equation][iteration]) - */ - std::vector > dependentIndexes_; - /** - * The indexed independent variables ([tape variable][iteration]) - */ - std::vector > indexedIndepIndexes_; - /** - * The non-indexed independent variables ([tape variable]) - */ - std::vector nonIndexedIndepIndexes_; - /** - * The independent variables related with temporary variables of the - * original model. - */ - std::vector temporaryIndependents_; - /** - * Maps the original dependent variable indexes to their positions in - * the loop - */ - std::map depOrigIndexes_; - /** - * - */ - std::vector > equationGroups_; - std::vector*> > iteration2eqGroups_; - /** - * iteration -> original indep index -> tape indexes - */ - std::vector > > iteration2orig2indexedIndepIndexes_; - /** - * Maps the original variable indexes to non-indexed variables - */ - std::map orig2nonIndexedIndepIndexes_; - /** - * Maps the temporary variable indexes to the tape indexes - */ - std::map orig2tempIndepIndexes_; - /** - * index patterns for the indexed independent variables - */ - std::vector indepIndexPatterns_; - /** - * index pattern for the dependent variables - */ - std::vector depIndexPatterns_; - /** - * Jacobian sparsity pattern of the tape - */ - std::vector > jacTapeSparsity_; - bool jacSparsity_; - /** - * Hessian sparsity pattern of the tape - */ - std::vector > hessTapeSparsity_; - bool hessSparsity_; -public: - - /** - * Creates a new atomic function that is responsible for defining the - * dependencies to calls of a user atomic function. - * - * @param name The atomic function name. - * @param fun The tape for a single loop iteration (loop model) - * @param iterationCount Number of loop iterations - * @param dependentOrigIndexes - * @param indexedIndepOrigIndexes - * @param nonIndexedIndepOrigIndexes - * @param temporaryIndependents - */ - LoopModel(ADFun* fun, - size_t iterationCount, - const std::vector >& dependentOrigIndexes, - const std::vector >& indexedIndepOrigIndexes, - const std::vector& nonIndexedIndepOrigIndexes, - const std::vector& temporaryIndependents) : - loopId_(createNewLoopId()), - fun_(fun), - iterationCount_(iterationCount), - m_(dependentOrigIndexes.size()), - dependentIndexes_(m_, std::vector(iterationCount)), - indexedIndepIndexes_(indexedIndepOrigIndexes.size(), std::vector(iterationCount)), - nonIndexedIndepIndexes_(nonIndexedIndepOrigIndexes.size()), - temporaryIndependents_(temporaryIndependents.size()), - iteration2orig2indexedIndepIndexes_(iterationCount), - jacSparsity_(false), - hessSparsity_(false) { - CPPADCG_ASSERT_KNOWN(fun != nullptr, "fun cannot be null"); - - /** - * dependents - */ - for (size_t i = 0; i < m_; i++) { - for (size_t it = 0; it < iterationCount_; it++) { - size_t orig = dependentOrigIndexes[i][it]; - dependentIndexes_[i][it] = LoopPosition(i, orig); - if (orig != std::numeric_limits::max()) // some equations are not present in all iterations - depOrigIndexes_[orig] = LoopIndexedPosition(dependentIndexes_[i][it].tape, - dependentIndexes_[i][it].original, - it); - } - } - - /** - * Must determine the equations which are present at the same iterations - * (some equations may not be present at some iterations) - */ - std::map, std::set, SetComparator > iterations2equations; - size_t lm = dependentIndexes_.size(); - - for (size_t i = 0; i < lm; i++) { - std::set iterations; - for (size_t it = 0; it < iterationCount_; it++) { - if (dependentIndexes_[i][it].original != std::numeric_limits::max()) { - iterations.insert(it); - } - } - iterations2equations[iterations].insert(i); - } - - equationGroups_.resize(iterations2equations.size()); - iteration2eqGroups_.resize(iterationCount_); - - std::map, std::set, SetComparator >::const_iterator itEqeIt; - size_t g = 0; - for (itEqeIt = iterations2equations.begin(); itEqeIt != iterations2equations.end(); ++itEqeIt, g++) { - const std::set& iterations = itEqeIt->first; - - IterEquationGroup& group = equationGroups_[g]; - group.index = g; - group.tapeI = itEqeIt->second; - group.iterations = iterations; - group.model = this; - - // map iterations to the equation groups - for (size_t itIt : iterations) { - iteration2eqGroups_[itIt].insert(&group); - } - } - - /** - * independents - */ - size_t nIndexed = indexedIndepOrigIndexes.size(); - - // indexed - for (size_t it = 0; it < iterationCount_; it++) { - for (size_t j = 0; j < nIndexed; j++) { - size_t orig = indexedIndepOrigIndexes[j][it]; - indexedIndepIndexes_[j][it] = LoopPosition(j, orig); - if (orig != std::numeric_limits::max()) //some variables are not present in all iterations - iteration2orig2indexedIndepIndexes_[it][orig].insert(j); - } - } - - // non-indexed - size_t nNonIndexed = nonIndexedIndepOrigIndexes.size(); - for (size_t j = 0; j < nNonIndexed; j++) { - size_t orig = nonIndexedIndepOrigIndexes[j]; - nonIndexedIndepIndexes_[j] = LoopPosition(nIndexed + j, orig); - orig2nonIndexedIndepIndexes_[orig] = &nonIndexedIndepIndexes_[j]; - } - - // temporary - for (size_t j = 0; j < temporaryIndependents.size(); j++) { - size_t k = temporaryIndependents[j]; - temporaryIndependents_[j] = LoopPosition(nIndexed + nNonIndexed + j, k); - orig2tempIndepIndexes_[k] = &temporaryIndependents_[j]; - } - } - - LoopModel(const LoopModel&) = delete; - LoopModel& operator=(const LoopModel&) = delete; - - /** - * Provides a unique identifier for this loop. - * - * @return a unique identifier ID - */ - inline size_t getLoopId() const { - return loopId_; - } - - /** - * Provides the number of iterations in the loop - * - * @return the number of iterations in the loop - */ - inline const size_t getIterationCount() const { - return iterationCount_; - } - - /** - * Provides the tape that represents the loop model - * - * @return the tape of the loop model - */ - inline ADFun& getTape() const { - return *fun_; - } - - /** - * Provides the number of dependent variables in the loop tape/model - * (number of equation patterns). - * - * @return the number of dependents in the loop model - * (number of equation patterns) - */ - inline size_t getTapeDependentCount() const { - return m_; - } - - /** - * Provides the number of independent variables in the loop tape/model - * (number of indexed + non-indexed + temporary variables). - * - * @return the number of independents in the loop model - */ - inline size_t getTapeIndependentCount() const { - return fun_->Domain(); - } - - /** - * Provides the dependent variables indexes ([tape equation][iteration]) - */ - inline const std::vector >& getDependentIndexes() const { - return dependentIndexes_; - } - - /** - * Provides groups of equations present at the same iterations - */ - inline const std::vector >& getEquationsGroups() const { - return equationGroups_; - } - - inline const std::vector*> >& getIterationEquationsGroup() const { - return iteration2eqGroups_; - } - - /** - * Provides the indexed independent variables ([tape variable][iteration]) - */ - inline const std::vector >& getIndexedIndepIndexes() const { - return indexedIndepIndexes_; - } - - /** - * Provides the non-indexed independent variables ([tape variable]) - */ - inline const std::vector& getNonIndexedIndepIndexes() const { - return nonIndexedIndepIndexes_; - } - - /** - * Provides the independent variables related with temporary variables of the - * original model. - */ - inline const std::vector& getTemporaryIndependents() const { - return temporaryIndependents_; - } - - /** - * Provides the locations where a dependent variable is used - * - * @param origI the dependent variable index in the original model - * @return the locations where a dependent variable is used - */ - inline const LoopIndexedPosition& getTapeDependentIndex(size_t origI) const { - return depOrigIndexes_.at(origI); - } - - inline const std::map& getOriginalDependentIndexes() const { - return depOrigIndexes_; - } - - /** - * Maps the original variable indexes to non-indexed variables - */ - inline const LoopPosition* getNonIndexedIndepIndexes(size_t origJ) const { - std::map::const_iterator it = orig2nonIndexedIndepIndexes_.find(origJ); - if (it != orig2nonIndexedIndepIndexes_.end()) { - return it->second; - } else { - return nullptr; - } - } - - /** - * Maps the temporary variable indexes to temporary variables - */ - inline const LoopPosition* getTempIndepIndexes(size_t k) const { - std::map::const_iterator it = orig2tempIndepIndexes_.find(k); - if (it != orig2tempIndepIndexes_.end()) { - return it->second; - } else { - return nullptr; - } - } - - /** - * Finds the local tape variable indexes which use a given model - * variable at a given iteration - * - * @param origJ the index of the variable in the original model - * @param iteration the iteration - * @return the indexes of tape variables where the variable is used - */ - inline const std::set& getIndexedTapeIndexes(size_t iteration, size_t origJ) const { - CPPADCG_ASSERT_UNKNOWN(iteration < iteration2orig2indexedIndepIndexes_.size()); - - const std::map >& itOrigs = iteration2orig2indexedIndepIndexes_[iteration]; - std::map >::const_iterator it = itOrigs.find(origJ); - if (it != itOrigs.end()) { - return it->second; - } else { - return EMPTYSET; - } - } - - /** - * Finds the local tape variable indexes which use a given model variable - * - * @param origJ the index of the variable in the original model - * @return all the indexed tape variables for each iteration where the - * variable is used - */ - inline std::map > getIndexedTapeIndexes(size_t origJ) const { - std::map > iter2TapeJs; - - for (size_t iter = 0; iter < iterationCount_; iter++) { - const std::map >& itOrigs = iteration2orig2indexedIndepIndexes_[iter]; - std::map >::const_iterator it = itOrigs.find(origJ); - if (it != itOrigs.end()) { - iter2TapeJs[iter] = it->second; - } - } - - return iter2TapeJs; - } - - inline void detectIndexPatterns() { - if (indepIndexPatterns_.size() > 0) - return; // already done - - indepIndexPatterns_.resize(indexedIndepIndexes_.size()); - for (size_t j = 0; j < indepIndexPatterns_.size(); j++) { - std::map indexes; - for (size_t it = 0; it < iterationCount_; it++) { - size_t orig = indexedIndepIndexes_[j][it].original; - if (orig != std::numeric_limits::max()) // some variables are not present in all iteration - indexes[it] = orig; - } - indepIndexPatterns_[j] = IndexPattern::detect(indexes); - } - - depIndexPatterns_.resize(dependentIndexes_.size()); - for (size_t j = 0; j < depIndexPatterns_.size(); j++) { - std::map indexes; - for (size_t it = 0; it < iterationCount_; it++) { - size_t e = dependentIndexes_[j][it].original; - if (e != std::numeric_limits::max()) // some equations are not present in all iteration - indexes[it] = e; - } - - depIndexPatterns_[j] = IndexPattern::detect(indexes); - } - } - - inline const std::vector& getDependentIndexPatterns() const { - return depIndexPatterns_; - } - - inline const std::vector& getIndependentIndexPatterns() const { - return indepIndexPatterns_; - } - - inline bool isTemporary(size_t tapeJ) const { - size_t nIndexed = indexedIndepIndexes_.size(); - size_t nNonIndexed = nonIndexedIndepIndexes_.size(); - - return nIndexed + nNonIndexed <= tapeJ; - } - - inline bool isIndexedIndependent(size_t tapeJ) const { - return tapeJ < indexedIndepIndexes_.size(); - } - - inline void evalJacobianSparsity() { - if (!jacSparsity_) { - jacTapeSparsity_ = jacobianSparsitySet >, CGB>(*fun_); - jacSparsity_ = true; - } - } - - inline const std::vector >& getJacobianSparsity() const { - return jacTapeSparsity_; - } - - inline void evalHessianSparsity() { - if (!hessSparsity_) { - size_t n = fun_->Domain(); - hessTapeSparsity_.resize(n); - - for (size_t g = 0; g < equationGroups_.size(); g++) { - equationGroups_[g].evalHessianSparsity(); - const std::vector >& ghess = equationGroups_[g].getHessianSparsity(); - for (size_t j = 0; j < n; j++) { - hessTapeSparsity_[j].insert(ghess[j].begin(), ghess[j].end()); - } - } - - hessSparsity_ = true; - } - } - - inline const std::vector >& getHessianSparsity() const { - return hessTapeSparsity_; - } - - virtual ~LoopModel() { - delete fun_; - for (size_t i = 0; i < indepIndexPatterns_.size(); i++) { - delete indepIndexPatterns_[i]; - } - for (size_t i = 0; i < depIndexPatterns_.size(); i++) { - delete depIndexPatterns_[i]; - } - } - - static inline void printOriginalVariableIndexes(std::ostringstream& ss, - const std::vector& indexes) { - for (size_t iter = 0; iter < indexes.size(); iter++) { - if (iter > 0) ss << ", "; - ss << indexes[iter].original; - } - } - -private: - - static size_t createNewLoopId() { - CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static size_t count = 0; - count++; - return count; - } - -}; - -template -const std::string LoopModel::ITERATION_INDEX_NAME("j"); - -template -const std::set LoopModel::EMPTYSET; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/patterns/loop_position.hpp b/ct_core/include/ct/external/cppad/cg/patterns/loop_position.hpp deleted file mode 100644 index 3cb9a25fe..000000000 --- a/ct_core/include/ct/external/cppad/cg/patterns/loop_position.hpp +++ /dev/null @@ -1,70 +0,0 @@ -#ifndef CPPAD_CG_LOOP_POSITION_INCLUDED -#define CPPAD_CG_LOOP_POSITION_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Variable position which does not change from iteration to iteration - */ -class LoopPosition { -public: - size_t tape; - size_t original; - - inline LoopPosition() : - tape(std::numeric_limits::max()), - original(std::numeric_limits::max()) { - } - - /** - * @param t Index in the loop tape - * @param o Index in the original tape - */ - inline LoopPosition(size_t t, size_t o) : - tape(t), - original(o) { - } -}; - -/** - * Variable position which changes from iteration to iteration - */ -class LoopIndexedPosition : public LoopPosition { -public: - size_t iteration; - - inline LoopIndexedPosition() : - LoopPosition(), - iteration(-1) { - } - - /** - * @param t Index in the loop tape - * @param o Index in the original tape - * @param it Iteration index - */ - inline LoopIndexedPosition(size_t t, size_t o, size_t it) : - LoopPosition(t, o), - iteration(it) { - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/range.hpp b/ct_core/include/ct/external/cppad/cg/range.hpp deleted file mode 100644 index b0e35d84d..000000000 --- a/ct_core/include/ct/external/cppad/cg/range.hpp +++ /dev/null @@ -1,207 +0,0 @@ -#ifndef CPPAD_CG_RANGE_INCLUDED -#define CPPAD_CG_RANGE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Combines ordered and non-overlapping regions of iteration indexes. - * - * @param iterRegions the existing iteration regions - * @param newIterRegions the iteration regions to be added - */ -inline void combineNonOverlapingIterationRanges(std::vector& iterRegions, - const std::vector& newIterRegions) { - if (iterRegions.empty()) { - iterRegions = newIterRegions; - return; - } else if (newIterRegions.empty()) { - return; - } - - /** - * regions are assumed to be ordered and non-overlapping - */ - std::vector::iterator itPos = iterRegions.begin(); - std::vector::const_iterator itNew; - for (itNew = newIterRegions.begin(); itNew != newIterRegions.end(); ++itNew) { - size_t pos = *itNew; - itPos = std::lower_bound(itPos, iterRegions.end(), pos); - if (itPos == iterRegions.end()) { - iterRegions.insert(iterRegions.end(), itNew, newIterRegions.end()); - break; // done - } else if (*itPos == pos) { - // same value -> must merge - itPos = iterRegions.erase(itPos); - } else { - itPos = iterRegions.insert(itPos, pos); - } - } - CPPADCG_ASSERT_UNKNOWN(iterRegions.size() % 2 == 0); -} - -/** - * Combines ordered regions of iteration indexes. - * - * @param iterRegions the existing iteration regions - * @param newIterRegions the iteration regions to be added - */ -inline void combineOverlapingIterationRanges(std::vector& iterRegions, - const std::vector& newIterRegions) { - if (iterRegions.empty()) { - iterRegions = newIterRegions; - return; - } else if (newIterRegions.empty()) { - return; - } - - std::vector > sorted; - for (size_t i = 0; i < iterRegions.size(); i += 2) { - sorted.insert(sorted.end(), std::make_pair(iterRegions[i], iterRegions[i + 1])); - } - - std::vector >::iterator begin = sorted.begin(); - for (size_t i = 0; i < newIterRegions.size(); i += 2) { - std::pair p(newIterRegions[i], newIterRegions[i + 1]); - begin = std::lower_bound(begin, sorted.end(), p); - begin = sorted.insert(begin, p); - begin++; - } - - std::vector > result; - result.reserve(sorted.size()); - result.push_back(sorted[0]); - for (size_t i = 1; i < sorted.size(); i++) { - const std::pair& curr = sorted[i]; // interval to be added - std::pair& top = result.back(); - - if (top.second == std::numeric_limits::max()) // avoid overflow - break; // done, nothing can be added - - // if current interval is not overlapping with stack top, - // push it to the stack - if (top.second + 1 < curr.first) { - result.push_back(curr); - } else if (top.second < curr.second) { - // Otherwise update the ending time of top if ending of current - // interval is more - top.second = curr.second; - } - } - - iterRegions.resize(result.size() * 2); - for (size_t i = 0; i < result.size(); i++) { - iterRegions[2 * i] = result[i].first; - iterRegions[2 * i + 1] = result[i].second; - } -} - -/** - * Determines the iteration regions not present in the provided iteration - * regions. - * - * @param iterRegions a vector filled with ordered and non-overlapping - * iteration regions each defined with pairs of integers - * (start1, end1, start2, end2, ...) - * @return the iterations not present in iterRegions - */ -inline std::vector invertIterationRanges(const std::vector& iterRegions) { - std::vector inverted; - if (iterRegions.empty()) { - inverted.resize(2); - inverted[1] = std::numeric_limits::max(); - return inverted; - } - - CPPADCG_ASSERT_UNKNOWN(iterRegions.size() % 2 == 0); - inverted.reserve(iterRegions.size() + 4); - - if (iterRegions[0] != 0) { - inverted.push_back(0); - inverted.push_back(iterRegions[0] - 1); - } - - for (size_t i = 2; i < iterRegions.size(); i += 2) { - CPPADCG_ASSERT_UNKNOWN(iterRegions[i - 1] < iterRegions[i]); - inverted.push_back(iterRegions[i - 1] + 1); - inverted.push_back(iterRegions[i] - 1); - } - - if (iterRegions.back() != std::numeric_limits::max()) { - inverted.push_back(iterRegions.back() + 1); - inverted.push_back(std::numeric_limits::max()); - } - - return inverted; -} - -/** - * Determines the iteration regions that an 'if' branch can be called for. - * - * @param bScope a node that marks the beginning of the if branch. It must - * be of type CGStartIfOp, CGElseIfOp or CGElseOp. - * @param iterationIndexOp the iteration index node used in the condition(s) - * @return the iteration regions - */ -template -inline std::vector ifBranchIterationRanges(const OperationNode* bScope, - IndexOperationNode*& iterationIndexOp) { - CGOpCode bOp = bScope->getOperationType(); - - if (bOp == CGOpCode::StartIf || bOp == CGOpCode::ElseIf) { - OperationNode* cond = bScope->getArguments()[bOp == CGOpCode::StartIf ? 0 : 1].getOperation(); - CPPADCG_ASSERT_UNKNOWN(cond->getOperationType() == CGOpCode::IndexCondExpr); - CPPADCG_ASSERT_UNKNOWN(cond->getArguments().size() == 1); - CPPADCG_ASSERT_UNKNOWN(cond->getArguments()[0].getOperation() != nullptr); - CPPADCG_ASSERT_UNKNOWN(cond->getArguments()[0].getOperation()->getOperationType() == CGOpCode::Index); - iterationIndexOp = static_cast*> (cond->getArguments()[0].getOperation()); - return cond->getInfo(); - - } else { - // else - CPPADCG_ASSERT_UNKNOWN(bOp == CGOpCode::Else); - - std::vector nonIterationRegions; - OperationNode* ifBranch = bScope->getArguments()[0].getOperation(); - do { - CGOpCode bbOp = ifBranch->getOperationType(); - OperationNode* cond = ifBranch->getArguments()[bbOp == CGOpCode::StartIf ? 0 : 1].getOperation(); - CPPADCG_ASSERT_UNKNOWN(cond->getOperationType() == CGOpCode::IndexCondExpr); - CPPADCG_ASSERT_UNKNOWN(cond->getArguments().size() == 1); - CPPADCG_ASSERT_UNKNOWN(cond->getArguments()[0].getOperation() != nullptr); - CPPADCG_ASSERT_UNKNOWN(cond->getArguments()[0].getOperation()->getOperationType() == CGOpCode::Index); - IndexOperationNode* indexOp = static_cast*> (cond->getArguments()[0].getOperation()); - CPPADCG_ASSERT_UNKNOWN(iterationIndexOp == nullptr || iterationIndexOp == indexOp); - iterationIndexOp = indexOp; - - combineOverlapingIterationRanges(nonIterationRegions, cond->getInfo()); - - ifBranch = ifBranch->getArguments()[0].getOperation(); - } while (ifBranch->getOperationType() == CGOpCode::ElseIf); - - CPPADCG_ASSERT_UNKNOWN(iterationIndexOp != nullptr); - - // invert - return invertIterationRanges(nonIterationRegions); - } - -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/scope_path_element.hpp b/ct_core/include/ct/external/cppad/cg/scope_path_element.hpp deleted file mode 100644 index 2c567bb35..000000000 --- a/ct_core/include/ct/external/cppad/cg/scope_path_element.hpp +++ /dev/null @@ -1,47 +0,0 @@ -#ifndef CPPAD_CG_SCOPE_PATH_INCLUDED -#define CPPAD_CG_SCOPE_PATH_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2013 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -class ScopePathElement { -public: - typedef typename CodeHandler::ScopeIDType ScopeIDType; -public: - // the color/index associated with the scope - ScopeIDType color; - // the node that marks the beginning of this scope - OperationNode* beginning; - // the node that marks the end of this scope - OperationNode* end; -public: - - inline ScopePathElement(ScopeIDType color = 0, - OperationNode* nEnd = nullptr, - OperationNode* nBegin = nullptr) : - color(color), - beginning(nBegin), - end(nEnd) { - } - -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/smart_containers.hpp b/ct_core/include/ct/external/cppad/cg/smart_containers.hpp deleted file mode 100644 index bb93ecf7c..000000000 --- a/ct_core/include/ct/external/cppad/cg/smart_containers.hpp +++ /dev/null @@ -1,315 +0,0 @@ -#ifndef CPPAD_CG_SMART_CONTAINERS_INCLUDED -#define CPPAD_CG_SMART_CONTAINERS_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2014 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Smart vector of pointers. - * Deletes all vector values on destruction. - */ -template -class SmartVectorPointer { -public: - typedef typename std::vector::iterator iterator; - typedef typename std::vector::const_iterator const_iterator; - typedef typename std::vector::reverse_iterator reverse_iterator; - typedef typename std::vector::const_reverse_iterator const_reverse_iterator; - std::vector v; - - inline SmartVectorPointer() { - } - - inline SmartVectorPointer(size_t size) : - v(size) { - } - - inline SmartVectorPointer(std::vector& v_) { - v.swap(v_); - } - - inline size_t size() const { - return v.size(); - } - - inline bool empty() const { - return v.empty(); - } - - inline void reserve(size_t n) { - v.reserve(n); - } - - inline void push_back(Base* x) { - v.push_back(x); - } - - inline Base* operator[](size_t n) const { - return v[n]; - } - - inline Base*& operator[](size_t n) { - return v[n]; - } - - inline iterator begin() { - return v.begin(); - } - - inline const_iterator begin() const { - return v.begin(); - } - - inline iterator end() { - return v.end(); - } - - inline const_iterator end() const { - return v.end(); - } - - inline reverse_iterator rbegin() { - return v.rbegin(); - } - - inline const_reverse_iterator rbegin() const { - return v.rbegin(); - } - - inline reverse_iterator rend() { - return v.rend(); - } - - inline const_reverse_iterator rend() const { - return v.rend(); - } - - inline std::vector release() { - std::vector v2; - v2.swap(v); - return v2; - } - - inline virtual ~SmartVectorPointer() { - for (size_t i = 0; i < v.size(); i++) { - delete v[i]; - } - } -}; - -/** - * Smart set of pointers. - * Deletes all set values on destruction. - */ -template -class SmartSetPointer { -public: - typedef typename std::set::iterator iterator; - std::set s; - - inline SmartSetPointer() { - } - - inline SmartSetPointer(std::set& s_) { - s.swap(s_); - } - - inline size_t size() const { - return s.size(); - } - - inline bool empty() const { - return s.empty(); - } - - inline iterator begin() const { - return s.begin(); - } - - inline iterator end() const { - return s.end(); - } - - inline std::pair insert(Base* x) { - return s.insert(x); - } - - inline void erase(iterator pos) { - s.erase(pos); - } - - inline size_t erase(Base* x) { - return s.erase(x); - } - - inline std::set release() { - std::set s2; - s2.swap(s); - return s2; - } - - inline virtual ~SmartSetPointer() { - typename std::set::const_iterator it; - for (it = s.begin(); it != s.end(); ++it) { - delete *it; - } - } -}; - -/** - * Smart set of pointers. - * Deletes all set values on destruction. - */ -template -class SmartListPointer { -public: - typedef typename std::list::iterator iterator; - typedef typename std::list::const_iterator const_iterator; - std::list l; - - inline SmartListPointer() { - } - - inline SmartListPointer(const std::set& l_) { - l.swap(l_); - } - - inline size_t size() const { - return l.size(); - } - - inline bool empty() const { - return l.empty(); - } - - inline void push_front(Base* x) { - l.push_front(x); - } - - inline void pop_front() { - l.pop_front(); - } - - inline void push_back(Base* x) { - l.push_back(x); - } - - inline void pop_back() { - l.pop_back(); - } - - inline iterator begin() { - return l.begin(); - } - - inline const_iterator begin() const { - return l.begin(); - } - - inline iterator end() { - return l.end(); - } - - inline const_iterator end() const { - return l.end(); - } - - inline std::list release() { - std::list l2; - l2.swap(l); - return l2; - } - - inline virtual ~SmartListPointer() { - typename std::list::const_iterator it; - for (it = l.begin(); it != l.end(); ++it) { - delete *it; - } - } -}; - -template -class SmartMapValuePointer { -public: - typedef typename std::map::iterator iterator; - typedef typename std::map::const_iterator const_iterator; - typedef typename std::map::reverse_iterator reverse_iterator; - typedef typename std::map::const_reverse_iterator const_reverse_iterator; - std::map m; - - inline size_t size() const { - return m.size(); - } - - inline bool empty() const { - return m.empty(); - } - - inline iterator begin() { - return m.begin(); - } - - inline const_iterator begin() const { - return m.begin(); - } - - inline iterator end() { - return m.end(); - } - - inline const_iterator end() const { - return m.end(); - } - - inline reverse_iterator rbegin() { - return m.rbegin(); - } - - inline const_reverse_iterator rbegin() const { - return m.rbegin(); - } - - inline reverse_iterator rend() { - return m.rend(); - } - - inline const_reverse_iterator rend() const { - return m.rend(); - } - - inline Value*& operator[](const Key& key) { - return m[key]; - } - - std::map release() { - std::map m2; - m2.swap(m); - return m2; - } - - inline virtual ~SmartMapValuePointer() { - typename std::map::const_iterator it; - for (it = m.begin(); it != m.end(); ++it) { - delete it->second; - } - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/solver.hpp b/ct_core/include/ct/external/cppad/cg/solver.hpp deleted file mode 100644 index 7658ab03a..000000000 --- a/ct_core/include/ct/external/cppad/cg/solver.hpp +++ /dev/null @@ -1,263 +0,0 @@ -#ifndef CPPAD_CG_SOLVER_INCLUDED -#define CPPAD_CG_SOLVER_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -#include -#include - -namespace CppAD { -namespace cg { - -template -inline CG CodeHandler::solveFor(OperationNode& expression, - OperationNode& var) { - using std::vector; - - // find code in expression - if (&expression == &var) - return CG(var); - - size_t bifurcations = std::numeric_limits::max(); // so that it is possible to enter the loop - - std::vector paths; - BidirGraph foundGraph; - OperationNode *root = &expression; - - while (bifurcations > 0) { - CPPADCG_ASSERT_UNKNOWN(root != nullptr); - - // find possible paths from expression to var - size_t oldBif = bifurcations; - bifurcations = 0; - foundGraph = findPathGraph(*root, var, bifurcations, 50000); - CPPADCG_ASSERT_UNKNOWN(oldBif > bifurcations); - - if (!foundGraph.contains(var)) { - std::cerr << "Missing variable " << var << std::endl; - printExpression(expression, std::cerr); - throw CGException("The provided variable ", var.getName() != nullptr ? ("(" + *var.getName() + ")") : "", " is not present in the expression"); - } - - // find a bifurcation which does not contain any other bifurcations - size_t bifPos = 0; - paths = foundGraph.findSingleBifurcation(*root, var, bifPos); - if (paths.empty()) { - throw CGException("The provided variable is not present in the expression"); - - } else if (paths.size() == 1) { - CPPADCG_ASSERT_UNKNOWN(paths[0][0].node == root); - CPPADCG_ASSERT_UNKNOWN(paths[0].back().node == &var); - - return solveFor(paths[0]); - - } else { - CPPADCG_ASSERT_UNKNOWN(paths.size() >= 1); - CPPADCG_ASSERT_UNKNOWN(paths[0].back().node == &var); - - CG expression2 = collectVariable(*root, paths[0], paths[1], bifPos); - root = expression2.getOperationNode(); - } - } - - CPPADCG_ASSERT_UNKNOWN(paths.size() == 1); - return solveFor(paths[0]); -} - -template -inline CG CodeHandler::solveFor(const SourceCodePath& path) { - - CG rightHs(0.0); - - for (size_t n = 0; n < path.size() - 1; ++n) { - const OperationPathNode& pnodeOp = path[n]; - size_t argIndex = path[n].argIndex; - const std::vector >& args = pnodeOp.node->getArguments(); - - CGOpCode op = pnodeOp.node->getOperationType(); - switch (op) { - case CGOpCode::Mul: - { - const Argument& other = args[argIndex == 0 ? 1 : 0]; - rightHs /= CG(other); - break; - } - case CGOpCode::Div: - if (argIndex == 0) { - const Argument& other = args[1]; - rightHs *= CG(other); - } else { - const Argument& other = args[0]; - rightHs = CG(other) / rightHs; - } - break; - - case CGOpCode::UnMinus: - rightHs *= Base(-1.0); - break; - case CGOpCode::Add: - { - const Argument& other = args[argIndex == 0 ? 1 : 0]; - rightHs -= CG(other); - break; - } - case CGOpCode::Alias: - // do nothing - break; - case CGOpCode::Sub: - { - if (argIndex == 0) { - rightHs += CG(args[1]); - } else { - rightHs = CG(args[0]) - rightHs; - } - break; - } - case CGOpCode::Exp: - rightHs = log(rightHs); - break; - case CGOpCode::Log: - rightHs = exp(rightHs); - break; - case CGOpCode::Pow: - { - if (argIndex == 0) { - // base - const Argument& exponent = args[1]; - if (exponent.getParameter() != nullptr && *exponent.getParameter() == Base(0.0)) { - throw CGException("Invalid zero exponent"); - } else if (exponent.getParameter() != nullptr && *exponent.getParameter() == Base(1.0)) { - continue; // do nothing - } else { - throw CGException("Unable to invert operation '", op, "'"); - /* - if (exponent.getParameter() != nullptr && *exponent.getParameter() == Base(2.0)) { - rightHs = sqrt(rightHs); // TODO: should -sqrt(rightHs) somehow be considered??? - } else { - rightHs = pow(rightHs, Base(1.0) / CG(exponent)); - } - */ - } - } else { - // - const Argument& base = args[0]; - rightHs = log(rightHs) / log(CG(base)); - } - break; - } - case CGOpCode::Sqrt: - rightHs *= rightHs; - break; - //case CGAcosOp: // asin(variable) - //case CGAsinOp: // asin(variable) - //case Atan: // atan(variable) - case CGOpCode::Cosh: // cosh(variable) - { - rightHs = log(rightHs + sqrt(rightHs * rightHs - Base(1.0))); // asinh - break; - //case Cos: // cos(variable) - } - case CGOpCode::Sinh: // sinh(variable) - rightHs = log(rightHs + sqrt(rightHs * rightHs + Base(1.0))); // asinh - break; - //case CGSinOp: // sin(variable) - case CGOpCode::Tanh: // tanh(variable) - rightHs = Base(0.5) * (log(Base(1.0) + rightHs) - log(Base(1.0) - rightHs)); // atanh - break; - //case CGTanOp: // tan(variable) - default: - throw CGException("Unable to invert operation '", op, "'"); - }; - } - - return rightHs; -} - -template -inline bool CodeHandler::isSolvable(OperationNode& expression, - OperationNode& var) { - size_t bifurcations = 0; - BidirGraph g = findPathGraph(expression, var, bifurcations); - - if(bifurcations == 0) { - size_t bifIndex = 0; - auto paths = g.findSingleBifurcation(expression, var, bifIndex); - if (paths.empty() || paths[0].empty()) - return false; - - return isSolvable(paths[0]); - } else { - // TODO: improve this - //bool v = isCollectableVariableAddSub(); - try { - solveFor(expression, var); - return true; - } catch(const CGException& e) { - return false; - } - } -} - -template -inline bool CodeHandler::isSolvable(const SourceCodePath& path) const { - for (size_t n = 0; n < path.size() - 1; ++n) { - const OperationPathNode& pnodeOp = path[n]; - size_t argIndex = path[n].argIndex; - const std::vector >& args = pnodeOp.node->getArguments(); - - CGOpCode op = pnodeOp.node->getOperationType(); - switch (op) { - case CGOpCode::Mul: - case CGOpCode::Div: - case CGOpCode::UnMinus: - case CGOpCode::Add: - case CGOpCode::Alias: - case CGOpCode::Sub: - case CGOpCode::Exp: - case CGOpCode::Log: - case CGOpCode::Sqrt: - case CGOpCode::Cosh: // cosh(variable) - case CGOpCode::Sinh: // sinh(variable) - case CGOpCode::Tanh: // tanh(variable) - break; - case CGOpCode::Pow: - { - if (argIndex == 0) { - // base - const Argument& exponent = args[1]; - if (exponent.getParameter() != nullptr && *exponent.getParameter() == Base(0.0)) { - return false; - } else if (exponent.getParameter() != nullptr && *exponent.getParameter() == Base(1.0)) { - break; - } else { - return false; - } - } else { - break; - } - break; - } - - default: - return false; - }; - } - return true; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/unary.hpp b/ct_core/include/ct/external/cppad/cg/unary.hpp deleted file mode 100644 index ff95aebf3..000000000 --- a/ct_core/include/ct/external/cppad/cg/unary.hpp +++ /dev/null @@ -1,44 +0,0 @@ -#ifndef CPPAD_CG_UNARY_INCLUDED -#define CPPAD_CG_UNARY_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -inline CG CG::operator+() const { - return CG (*this); // nothing to do -} - -template -inline CG CG::operator-() const { - if (isParameter()) { - return CG (-getValue()); - - } else { - CodeHandler& h = *getCodeHandler(); - CG result(*h.makeNode(CGOpCode::UnMinus, this->argument())); - if (isValueDefined()) { - result.setValue(-getValue()); - } - return result; - } -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/util.hpp b/ct_core/include/ct/external/cppad/cg/util.hpp deleted file mode 100644 index f306ea480..000000000 --- a/ct_core/include/ct/external/cppad/cg/util.hpp +++ /dev/null @@ -1,677 +0,0 @@ -#ifndef CPPAD_CG_UTIL_INCLUDED -#define CPPAD_CG_UTIL_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -void zeroOrderDependency(ADFun& fun, - const VectorBool& vx, - VectorBool& vy) { - size_t m = fun.Range(); - CPPADCG_ASSERT_KNOWN(vx.size() >= fun.Domain(), "Invalid vx size"); - CPPADCG_ASSERT_KNOWN(vy.size() >= m, "Invalid vy size"); - - typedef std::vector > VectorSet; - - const VectorSet jacSparsity = jacobianSparsitySet(fun); - - for (size_t i = 0; i < m; i++) { - for (size_t j : jacSparsity[i]) { - if (vx[j]) { - vy[i] = true; - break; - } - } - } -} - -template -inline bool isIdentityPattern(const VectorSet& pattern, - size_t mRows) { - CPPADCG_ASSERT_UNKNOWN(pattern.size() >= mRows); - - for (size_t i = 0; i < mRows; i++) { - if (pattern[i].size() != 1 || *pattern[i].begin() != i) { - return false; - } - } - return true; -} - -template -inline VectorSet transposePattern(const VectorSet& pattern, - size_t mRows, - size_t nCols) { - CPPADCG_ASSERT_UNKNOWN(pattern.size() >= mRows); - - VectorSet transpose(nCols); - for (size_t i = 0; i < mRows; i++) { - for (size_t it : pattern[i]) { - transpose[it].insert(i); - } - } - return transpose; -} - -template -inline void transposePattern(const VectorSet& pattern, - size_t mRows, - VectorSet2& transpose) { - CPPADCG_ASSERT_UNKNOWN(pattern.size() >= mRows); - - for (size_t i = 0; i < mRows; i++) { - for (size_t it : pattern[i]) { - transpose[it].insert(i); - } - } -} - -template -inline void transposePattern(const VectorSet& pattern, - VectorSet2& transpose) { - transposePattern(pattern, pattern.size(), transpose); -} - -/** - * Computes the resulting sparsity from adding one matrix to another: - * R += A - * - * @param a The matrix to be added to the result - * @param result the resulting sparsity matrix - */ -template -inline void addMatrixSparsity(const VectorSet& a, - VectorSet2& result) { - CPPADCG_ASSERT_UNKNOWN(result.size() == a.size()); - - for (size_t i = 0; i < a.size(); i++) { - result[i].insert(a[i].begin(), a[i].end()); - } -} - -/** - * Computes the resulting sparsity from the multiplying of two matrices: - * R += A * B - * - * @param a The left matrix in the multiplication - * @param b The right matrix in the multiplication - * @param result the resulting sparsity matrix - * @param q The number of columns of B and the result - */ -template -inline void multMatrixMatrixSparsity(const VectorSet& a, - const VectorSet2& b, - CppAD::vector >& result, - size_t q) { - multMatrixMatrixSparsity(a, b, result, a.size(), b.size(), q); -} - -/** - * Computes the resulting sparsity from the multiplying of two matrices: - * R += A * B - * - * Optimized for when the B matrix has less elements than A. - * - * @param a The left matrix in the multiplication - * @param b The right matrix in the multiplication - * @param result the resulting sparsity matrix - * @param m The number of rows of A - * @param n The number of columns of A and rows of B - * @param q The number of columns of B and the result - */ -template -inline void multMatrixMatrixSparsity(const VectorSet& a, - const VectorSet2& b, - CppAD::vector >& result, - size_t m, - size_t n, - size_t q) { - CPPADCG_ASSERT_UNKNOWN(a.size() >= m); - CPPADCG_ASSERT_UNKNOWN(b.size() >= n); - CPPADCG_ASSERT_UNKNOWN(result.size() >= m); - - //check if b is identity - if (n == q) { - if (isIdentityPattern(b, n)) { - for (size_t i = 0; i < m; i++) { - result[i] = a[i]; - } - return; - } - } - - VectorSet2 bt = transposePattern(b, n, q); - - for (size_t jj = 0; jj < q; jj++) { //loop columns of b - const std::set& colB = bt[jj]; - if (colB.size() > 0) { - for (size_t i = 0; i < m; i++) { - const std::set& rowA = a[i]; - for (size_t rowb : colB) { - if (rowA.find(rowb) != rowA.end()) { - result[i].insert(jj); - break; - } - } - } - } - } -} - -/** - * Computes the resulting sparsity from multiplying two matrices: - * R += A^T * B - * - * Optimized for when the B matrix has less elements than A. - * - * @param a The left matrix in the multiplication - * @param b The right matrix in the multiplication - * @param result the resulting sparsity matrix - * @param m The number of rows of A and rows of B - * @param n The number of columns of A and rows of the result - * @param q The number of columns of B and the result - */ -template -inline void multMatrixTransMatrixSparsity(const VectorSet& a, - const VectorSet2& b, - CppAD::vector >& result, - size_t m, - size_t n, - size_t q) { - CPPADCG_ASSERT_UNKNOWN(a.size() >= m); - CPPADCG_ASSERT_UNKNOWN(b.size() >= m); - CPPADCG_ASSERT_UNKNOWN(result.size() >= n); - - //check if B is empty - bool empty = true; - for (size_t i = 0; i < m; i++) { - if (b[i].size() > 0) { - empty = false; - break; - } - } - if (empty) { - return; //nothing to do - } - - //check if A is identity - if (m == n && isIdentityPattern(a, m)) { - for (size_t i = 0; i < n; i++) { - result[i] = b[i]; - } - return; - } - - //check if B is identity - if (m == q && isIdentityPattern(b, m)) { - transposePattern(a, m, result); - return; - } - - VectorSet at = transposePattern(a, m, n); - VectorSet2 bt = transposePattern(b, m, q); - - for (size_t jj = 0; jj < q; jj++) { //loop columns of b - const std::set& colB = bt[jj]; - if (colB.size() > 0) { - for (size_t i = 0; i < n; i++) { - const std::set& rowAt = at[i]; - if (rowAt.size() > 0) { - for (size_t rowb : colB) { - if (rowAt.find(rowb) != rowAt.end()) { - result[i].insert(jj); - break; - } - } - } - } - } - } - -} - -/** - * Computes the transpose of the resulting sparsity from multiplying two - * matrices: - * (R += A * B)^T - * - * @param a The TRANSPOSE of the left matrix in the multiplication - * @param b The right matrix in the multiplication - * @param result the TRANSPOSE of the resulting sparsity matrix - * @param m The number of rows of B - * @param n The number of columns of B - * @param q The number of rows of A and the result - */ -template -inline void multMatrixMatrixSparsityTrans(const VectorSet& aT, - const VectorSet2& b, - CppAD::vector >& rT, - size_t m, - size_t n, - size_t q) { - CPPADCG_ASSERT_UNKNOWN(aT.size() >= m); - CPPADCG_ASSERT_UNKNOWN(b.size() >= m); - - //check if b is empty - bool empty = true; - for (size_t i = 0; i < m; i++) { - if (b[i].size() > 0) { - empty = false; - break; - } - } - if (empty) { - return; //nothing to do - } - - //check if a is identity - if (m == q && isIdentityPattern(aT, m)) { - transposePattern(b, m, rT); - return; - } - - VectorSet a = transposePattern(aT, m, q); - VectorSet2 bT = transposePattern(b, m, n); - - for (size_t jj = 0; jj < n; jj++) { //loop columns of b - for (size_t i = 0; i < q; i++) { - for (size_t it : a[i]) { - if (bT[jj].find(it) != bT[jj].end()) { - rT[jj].insert(i); - break; - } - } - } - } -} - -template -void printSparsityPattern(const VectorBool& sparsity, - const std::string& name, - size_t m, size_t n) { - size_t width = std::ceil(std::log10((m > n) ? m : n)); - if (!name.empty()) { - std::cout << name << " sparsity:\n"; - } - for (size_t i = 0; i < m; i++) { - std::cout << " " << std::setw(width) << i << ": "; - for (size_t j = 0; j < n; j++) { - if (sparsity[i * n + j]) { - std::cout << std::setw(width) << j << " "; - } else { - std::cout << std::setw(width) << " " << " "; - } - } - std::cout << "\n"; - } - std::cout << std::endl; -} - -template -void printSparsityPattern(const VectorSet& sparsity, - const std::string& name, - bool printLocationByRow = false) { - size_t maxDim = sparsity.size(); - size_t nnz = 0; - for (size_t i = 0; i < sparsity.size(); i++) { - if (sparsity[i].size() > 0 && *sparsity[i].rbegin() > maxDim) { - maxDim = *sparsity[i].rbegin(); - } - nnz += sparsity[i].size(); - } - - size_t width = std::ceil(std::log10(maxDim)); - size_t width2; - size_t width3 = width; - if (printLocationByRow) { - width2 = std::ceil(std::log10(nnz)); - width3 += width2 + 1; - } - if (!name.empty()) { - std::cout << name << " sparsity:\n"; - } - - size_t e = 0; - for (size_t i = 0; i < sparsity.size(); i++) { - std::cout << " " << std::setw(width) << i << ": "; - long last = -1; - for (size_t j : sparsity[i]) { - if (j != 0 && long(j) != last + 1) { - std::cout << std::setw((j - last - 1) * (width3 + 1)) << " "; - } - if (printLocationByRow) - std::cout << std::setw(width2) << e << ":"; - std::cout << std::setw(width) << j << " "; - last = j; - e++; - } - std::cout << "\n"; - } - std::cout << std::endl; -} - -template -void printSparsityPattern(const VectorSize& row, - const VectorSize& col, - const std::string& name, - size_t m) { - std::vector > sparsity(m); - generateSparsitySet(row, col, sparsity); - printSparsityPattern(sparsity, name); -} - -inline bool intersects(const std::set& a, - const std::set& b) { - if (a.empty() || b.empty()) { - return false; - } else if (*a.rbegin() < *b.begin() || - *a.begin() > *b.rbegin()) { - return false; - } - - if (a.size() < b.size()) { - for (size_t ita : a) { - if (b.find(ita) != b.end()) { - return true; - } - } - } else { - for (size_t itb : b) { - if (a.find(itb) != a.end()) { - return true; - } - } - } - - return false; -} - -/** - * Finds the first non-null code handler - * - * @param ty The array to search in - * @return The first code handler found or nullptr if none was found - */ -template -inline CodeHandler* findHandler(const std::vector >& ty) { - for (size_t i = 0; i < ty.size(); i++) { - if (ty[i].getCodeHandler() != nullptr) { - return ty[i].getCodeHandler(); - } - } - return nullptr; -} - -template -inline CodeHandler* findHandler(const CppAD::vector >& ty) { - for (size_t i = 0; i < ty.size(); i++) { - if (ty[i].getCodeHandler() != nullptr) { - return ty[i].getCodeHandler(); - } - } - return nullptr; -} - -template -inline Argument asArgument(const CG& tx) { - if (tx.isParameter()) { - return Argument(tx.getValue()); - } else { - return Argument(*tx.getOperationNode()); - } -} - -template -inline std::vector > asArguments(const std::vector >& tx) { - std::vector > arguments(tx.size()); - for (size_t i = 0; i < arguments.size(); i++) { - arguments[i] = asArgument(tx[i]); - } - return arguments; -} - -template -inline std::vector > asArguments(const CppAD::vector >& tx) { - std::vector > arguments(tx.size()); - for (size_t i = 0; i < arguments.size(); i++) { - arguments[i] = asArgument(tx[i]); - } - return arguments; -} - -/*************************************************************************** - * map related - **************************************************************************/ - -/** - * Gets all the keys present in a map - * - * @param map the map from which to get the keys from - * @param keys the map keys will be inserted into this set - */ -template -void mapKeys(const std::map& map, std::set& keys) { - for (const auto& p : map) { - keys.insert(keys.end(), p.first); - } -} - -/** - * Gets all the keys present in a map - * - * @param map the map from which to get the keys from - * @param keys the map keys will be saved in this vector - */ -template -void mapKeys(const std::map& map, std::vector& keys) { - keys.resize(map.size()); - - size_t i = 0; - typename std::map::const_iterator it; - for (it = map.begin(); it != map.end(); ++it, i++) { - keys[i] = it->first; - } -} - -/** - * Checks if a map has only a set of keys. - * - * @param map The map - * @param keys The keys - * @return true if all the keys and only these keys where found in the map - */ -template -bool compareMapKeys(const std::map& map, const std::set& keys) { - if (map.size() != keys.size()) - return false; - - typename std::map::const_iterator itm = map.begin(); - typename std::set::const_iterator itk = keys.begin(); - for (; itm != map.end(); ++itm, ++itk) { - if (itm->first != *itk) - return false; - } - - return true; -} - -/** - * Creates a new map with only a given set of keys - * - * @param m The map to be filtered - * @param keys the keys (the filter) to be retrieved from the map - * @return a new map only with the keys found in provided filter - */ -template -inline std::map filterBykeys(const std::map& m, - const std::set& keys) { - std::map filtered; - - typename std::map::const_iterator itM; - - for (const Key& k : keys) { - itM = m.find(k); - if (itM != m.end()) { - filtered[itM->first] = itM->second; - } - } - return filtered; -} - -/** - * Compares two sets - * - * @param s1 the first set - * @param s2 the second set - * @return -1 if the first set is considered lower than the second, - * 0 if they have all the same elements - * 1 if the second set is considered lower than the first. - */ -template -inline int compare(const std::set& s1, const std::set& s2) { - if (s1.size() < s2.size()) { - return -1; - } else if (s1.size() > s2.size()) { - return 1; - } else { - typename std::set::const_iterator it1, it2; - for (it1 = s1.begin(), it2 = s2.begin(); it1 != s1.end(); ++it1, ++it2) { - if (*it1 < *it2) { - return -1; - } else if (*it1 > *it2) { - return 1; - } - } - return 0; - } -} - -template -struct SetComparator { - - bool operator() (const std::set& lhs, const std::set& rhs) const { - return compare(lhs, rhs) == -1; - } -}; - -/*************************************************************************** - * Generic functions for printing stl containers - **************************************************************************/ -template -inline void print(const Base& v) { - std::cout << v; -} - -template -inline void print(const std::map& m) { - for (const std::pair& p : m) { - std::cout << p.first << " : "; - print(p.second); - std::cout << std::endl; - } -} - -template -inline void print(const std::set& s) { - std::cout << "["; - - for (auto itj = s.begin(); itj != s.end(); ++itj) { - if (itj != s.begin()) std::cout << " "; - print(*itj); - } - std::cout << "]"; - std::cout.flush(); -} - -template -inline void print(const std::set& s) { - std::cout << "["; - - for (const auto itj = s.begin(); itj != s.end(); ++itj) { - if (itj != s.begin()) std::cout << " "; - Base* v = *itj; - if (v == nullptr) std::cout << "NULL"; - else print(*v); - } - std::cout << "]"; - std::cout.flush(); -} - -template -inline void print(const std::vector& v) { - std::cout << "["; - - for (size_t i = 0; i < v.size(); i++) { - if (i != 0) std::cout << " "; - print(v[i]); - } - std::cout << "]"; - std::cout.flush(); -} - -/*************************************************************************** - * String related utilities - **************************************************************************/ - -/** - * Replaces all occurrence of a string. - * - * @param text the text where the search and replacement will be performed - * @param toReplace the text to be replaced - * @param replacement the replacement text - */ -inline void replaceString(std::string& text, - const std::string& toReplace, - const std::string& replacement) { - size_t pos = 0; - while ((pos = text.find(toReplace, pos)) != std::string::npos) { - text.replace(pos, toReplace.length(), replacement); - pos += replacement.length(); - } -} - -inline std::vector explode(const std::string& text, - const std::string& delimiter) { - std::vector matches; - - const size_t dlen = delimiter.length(); - if (dlen == 0) - return matches; - - size_t pos = 0; - size_t start = 0; - while (true) { - pos = text.find(delimiter, start); - if (pos == std::string::npos) { - break; - } - matches.push_back(text.substr(start, pos - start)); - start = pos + dlen; - } - - if (start < text.length()) { - matches.push_back(text.substr(start, text.length() - start)); - } - - return matches; -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/variable.hpp b/ct_core/include/ct/external/cppad/cg/variable.hpp deleted file mode 100644 index 6c2319ca2..000000000 --- a/ct_core/include/ct/external/cppad/cg/variable.hpp +++ /dev/null @@ -1,109 +0,0 @@ -#ifndef CPPAD_CG_VARIABLE_INCLUDED -#define CPPAD_CG_VARIABLE_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -template -inline CodeHandler* CG::getCodeHandler() const { - if (node_ != nullptr) - return node_->getCodeHandler(); - else - return nullptr; -} - -template -inline bool CG::isVariable() const { - return node_ != nullptr; -} - -template -inline bool CG::isParameter() const { - return node_ == nullptr; -} - -template -inline bool CG::isValueDefined() const { - return value_ != nullptr; -} - -template -inline const Base& CG::getValue() const { - if (!isValueDefined()) { - throw CGException("No value defined for this variable"); - } - - return *value_; -} - -template -inline void CG::setValue(const Base& b) { - if (value_ != nullptr) { - *value_ = b; - } else { - value_ = new Base(b); - } -} - -template -inline bool CG::isIdenticalZero() const { - return isParameter() && CppAD::IdenticalZero(getValue()); -} - -template -inline bool CG::isIdenticalOne() const { - return isParameter() && CppAD::IdenticalOne(getValue()); -} - -template -inline void CG::makeParameter(const Base &b) { - node_ = nullptr; - setValue(b); -} - -template -inline void CG::makeVariable(OperationNode& operation) { - node_ = &operation; - delete value_; - value_ = nullptr; -} - -template -inline void CG::makeVariable(OperationNode& operation, - std::unique_ptr& value) { - node_ = &operation; - delete value_; - value_ = value.release(); -} - -template -inline OperationNode* CG::getOperationNode() const { - return node_; -} - -template -inline Argument CG::argument() const { - if (node_ != nullptr) - return Argument (*node_); - else - return Argument (*value_); -} - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/cg/variable_name_generator.hpp b/ct_core/include/ct/external/cppad/cg/variable_name_generator.hpp deleted file mode 100644 index 1abd04690..000000000 --- a/ct_core/include/ct/external/cppad/cg/variable_name_generator.hpp +++ /dev/null @@ -1,328 +0,0 @@ -#ifndef CPPAD_CG_VARIABLE_NAME_GENERATOR_INCLUDED -#define CPPAD_CG_VARIABLE_NAME_GENERATOR_INCLUDED -/* -------------------------------------------------------------------------- - * CppADCodeGen: C++ Algorithmic Differentiation with Source Code Generation: - * Copyright (C) 2012 Ciengis - * - * CppADCodeGen is distributed under multiple licenses: - * - * - Eclipse Public License Version 1.0 (EPL1), and - * - GNU General Public License Version 3 (GPL3). - * - * EPL1 terms and conditions can be found in the file "epl-v10.txt", while - * terms and conditions for the GPL3 can be found in the file "gpl3.txt". - * ---------------------------------------------------------------------------- - * Author: Joao Leal - */ - -namespace CppAD { -namespace cg { - -/** - * Function arguments - */ -typedef struct FuncArgument { - std::string name; - bool array; - - inline FuncArgument() : - array(false) { - } - - inline FuncArgument(const std::string& nam, bool a = true) : - name(nam), - array(a) { - } -} FuncArgument; - -/** - * Creates variables names for the source code. - * - * @author Joao Leal - */ -template -class VariableNameGenerator { -protected: - std::vector _dependent; - std::vector _independent; - std::vector _temporary; -public: - - /** - * Provides the dependent variable arguments used by a function. - * - * @return the dependent variable arguments - */ - virtual const std::vector& getDependent() const { - return _dependent; - } - - /** - * Provides the independent variable arguments used by a function. - * - * @return the independent variable arguments - */ - virtual const std::vector& getIndependent() const { - return _independent; - } - - /** - * Provides the temporary variable arguments used by a function. - * - * @return the temporary variable arguments - */ - virtual const std::vector& getTemporary() const { - return _temporary; - } - - /** - * Provides the minimum variable ID of temporary variables. - */ - virtual size_t getMinTemporaryVariableID() const = 0; - - /** - * Provides the maximum used variable ID of temporary variables. - */ - virtual size_t getMaxTemporaryVariableID() const = 0; - - /** - * Provides the maximum variable ID of temporary dense array variables. - */ - virtual size_t getMaxTemporaryArrayVariableID() const = 0; - - /** - * Provides the maximum variable ID of temporary sparse array variables. - */ - virtual size_t getMaxTemporarySparseArrayVariableID() const = 0; - - /** - * Creates a name for a dependent variable. - * - * @param index the dependent variable index - * @return the generated name - */ - virtual std::string generateDependent(size_t index) = 0; - - /** - * Creates a name for a dependent variable. - * - * @param variable the node representing the independent variable - * @param id an ID assigned by the CodeHandler to the operation node - * (unique for independent variables) - * @return the generated name - */ - virtual std::string generateIndependent(const OperationNode& variable, - size_t id) = 0; - - /** - * Creates a name for a temporary variable. - * - * @param variable the node representing the temporary variable - * @param id an ID assigned by the CodeHandler to the operation node - * (potentially not unique) - * @return the generated name - */ - virtual std::string generateTemporary(const OperationNode& variable, - size_t id) = 0; - - /** - * Creates a name for a temporary dense array variable. - * - * @param variable the node representing the dense array variable creation - * @param id an ID assigned by the CodeHandler to the operation node - * (potentially not unique) - * @return the generated name - */ - virtual std::string generateTemporaryArray(const OperationNode& variable, - size_t id) = 0; - - /** - * Creates a name for a temporary sparse array variable. - * - * @param variable the node representing the sparse array variable creation - * @param id an ID assigned by the CodeHandler to the operation node - * (potentially not unique) - * @return the generated name - */ - virtual std::string generateTemporarySparseArray(const OperationNode& variable, - size_t id) = 0; - - /** - * Creates a name for a reference to an indexed dependent variable - * expression. - * - * @param var the node representing an indexed dependent variable - * @param id an ID assigned by the CodeHandler to the operation node - * (potentially not unique) - * @param ip the index pattern - * @return the generated name - */ - virtual std::string generateIndexedDependent(const OperationNode& var, - size_t id, - const IndexPattern& ip) = 0; - - /** - * Creates a name for a reference to an indexed independent variable - * expression. - * - * @param var the node representing an indexed independent variable - * @param id an ID assigned by the CodeHandler to the operation node - * (unique for indexed independent variables) - * @param ip the index pattern - * @return the generated name - */ - virtual std::string generateIndexedIndependent(const OperationNode& var, - size_t id, - const IndexPattern& ip) = 0; - - /** - * Defines the ID ranges used by each variable type. - * - * @param minTempID the lowest ID of temporary variables - * @param maxTempID the highest used ID of temporary variables - * @param maxTempArrayID the highest used ID of temporary dense array - * variables - * @param maxTempSparseArrayID the highest used ID of temporary sparse - * array variables - */ - virtual void setTemporaryVariableID(size_t minTempID, - size_t maxTempID, - size_t maxTempArrayID, - size_t maxTempSparseArrayID) = 0; - - /** - * Provides the array name where independent variables are provided to the - * function. - * It should only be called if independents are saved in an array. - * - * @param indep the independent variable node (CGInvOp) - * @param id an ID assigned by the CodeHandler to the operation node - * (unique for independent variable arrays) - * @return the array name - */ - virtual const std::string& getIndependentArrayName(const OperationNode& indep, - size_t id) = 0; - - /** - * Provides the index in the associated independent array of an - * independent variable. - * It should only be called if independents are saved in an array. - * - * @param indep the independent variable node (CGInvOp) - * @param id an ID assigned by the CodeHandler to the operation node - * (unique for independent variable arrays) - * @return the index - */ - virtual size_t getIndependentArrayIndex(const OperationNode& indep, - size_t id) = 0; - - /** - * Whether or not two independent variables are considered to be part of - * the same independent variable array at consecutive locations. - * - * @param indepFirst the independent node (CGInvOp) with the lower index - * @param idFirst an ID assigned by the CodeHandler to the first node - * (unique for independent variables) - * @param indepSecond the independent node (CGInvOp) with the higher index - * @param idSecond an ID assigned by the CodeHandler to the second node - * (unique for independent variables) - * @return true if the independents are consecutive - */ - virtual bool isConsecutiveInIndepArray(const OperationNode& indepFirst, - size_t idFirst, - const OperationNode& indepSecond, - size_t idSecond) = 0; - - /** - * Determines whether or not two independents are part of the same - * independent variable array. - * - * @param indep1 the first independent node (CGInvOp or CGLoopIndexedIndepOp) - * @param id1 an ID assigned by the CodeHandler to indep1 - * (unique for independent variables) - * @param indep2 the second independent node (CGInvOp or CGLoopIndexedIndepOp) - * @param id2 an ID assigned by the CodeHandler to indep2 - * (unique for independent variables) - * @return true if the independents are part of the same array - */ - virtual bool isInSameIndependentArray(const OperationNode& indep1, - size_t id1, - const OperationNode& indep2, - size_t id2) = 0; - - /** - * Provides the array name for the temporary variables. - * It should only be called if temporary variables are saved in an array. - * - * @param var the temporary variable node - * @param id an ID assigned by the CodeHandler to the operation node - * (potentially not unique) - * @return the array name - */ - virtual const std::string& getTemporaryVarArrayName(const OperationNode& var, - size_t id) = 0; - - /** - * Provides the index in the associated temporary array of a temporary - * variable. - * It should only be called if temporary variables are saved in an array. - * - * @param var the temporary variable node - * @param id an ID assigned by the CodeHandler to the operation node - * (potentially not unique) - * @return the index - */ - virtual size_t getTemporaryVarArrayIndex(const OperationNode& var, - size_t id) = 0; - - /** - * Whether or not two temporary variables are considered to be part of - * the same temporary variable array at consecutive locations. - * - * @param varFirst the temporary variable node with the lower index - * @param idFirst an ID assigned by the CodeHandler to the first node - * (potentially not unique) - * @param varSecond the temporary variable node with the higher index - * @param varSecond an ID assigned by the CodeHandler to the second node - * (potentially not unique) - * @return true if they are consecutive - */ - virtual bool isConsecutiveInTemporaryVarArray(const OperationNode& varFirst, - size_t idFirst, - const OperationNode& varSecond, - size_t idSecond) = 0; - - /** - * Determines whether or not two temporary variables are part of the same - * temporary variable array. - * - * @param var1 the temporary variable node - * @param id1 an ID assigned by the CodeHandler to var1 - * (potentially not unique) - * @param var2 the temporary variable node - * @param id2 an ID assigned by the CodeHandler to var2 - * (potentially not unique) - * @return true if the temporary variables are part of the same array - */ - virtual bool isInSameTemporaryVarArray(const OperationNode& var1, - size_t id1, - const OperationNode& var2, - size_t id2) = 0; - - virtual void customFunctionVariableDeclarations(std::ostream& out) { - } - - virtual void prepareCustomFunctionVariables(std::ostream& out) { - } - - virtual void finalizeCustomFunctionVariables(std::ostream& out) { - } - - inline virtual ~VariableNameGenerator() { - } -}; - -} // END cg namespace -} // END CppAD namespace - -#endif \ No newline at end of file diff --git a/ct_core/include/ct/external/cppad/configure.hpp b/ct_core/include/ct/external/cppad/configure.hpp deleted file mode 100644 index a642532c4..000000000 --- a/ct_core/include/ct/external/cppad/configure.hpp +++ /dev/null @@ -1,218 +0,0 @@ -// $Id: configure.hpp.in 3760 2015-12-01 04:12:28Z bradbell $ -# ifndef CPPAD_CONFIGURE_HPP -# define CPPAD_CONFIGURE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin configure$$ -$spell - CppAD -$$ - -$section Configuration Preprocessor Symbols Used by CppAD$$ - -$head Preprocessor Symbols$$ -All of the preprocessor symbols used by CppAD begin with -$code CPPAD_$$ -(there are some deprecated symbols that begin with $code CppAD$$). - -$end -*/ - -/*! - \file configure.hpp -Replacement for config.h so that all preprocessor symbols begin with CPPAD_ -*/ - -/*! -\def CPPAD_DISABLE_SOME_MICROSOFT_COMPILER_WARNINGS -This macro is only used to document the pragmas that disables the -follow warnings: - -\li C4100 -unreferenced formal parameter. -\li C4127 -conditional expression is constant. -*/ -# define CPPAD_DISABLE_SOME_MICROSOFT_COMPILER_WARNINGS 1 -# if _MSC_VER -# pragma warning( disable : 4100 ) -# pragma warning( disable : 4127 ) -# endif -# undef CPPAD_DISABLE_SOME_MICROSOFT_COMPILER_WARNINGS - -/*! -\def CPPAD_USE_CPLUSPLUS_2011 -Should CppAD use C++11 features. This will be true if the current -compiler flags request C++11 features and the install procedure -determined that all the necessary features are avaiable. -*/ -# if _MSC_VER -# define CPPAD_USE_CPLUSPLUS_2011 0 -# else // -# if __cplusplus >= 201100 -# define CPPAD_USE_CPLUSPLUS_2011 0 -# else // -# define CPPAD_USE_CPLUSPLUS_2011 0 -# endif // -# endif // - -/*! -\def CPPAD_PACKAGE_STRING -cppad-yyyymmdd as a C string where yyyy is year, mm is month, and dd is day. -*/ -# define CPPAD_PACKAGE_STRING "cppad-20160000.1" - -/*! -def CPPAD_HAS_COLPACK -Was a colpack_prefix specified on the cmake command line. -*/ -# define CPPAD_HAS_COLPACK 0 - -/*! -def CPPAD_INTERNAL_SPARSE_SET -is the internal representation used for sparse vectors of std::set -either sparse_set or sparse_list). -*/ -# define CPPAD_INTERNAL_SPARSE_SET sparse_list - -/*! -\def CPPAD_DEPRECATED -If this symbol is one, an implicit constor of AD is defined -where the argument has any type. -Otherwise this constructor is explicit. -*/ -# define CPPAD_DEPRECATED 0 - -/*! -\def CPPAD_BOOSTVECTOR -If this symbol is one, and _MSC_VER is not defined, -we are using boost vector for CPPAD_TESTVECTOR. -It this symbol is zero, -we are not using boost vector for CPPAD_TESTVECTOR. -*/ -# define CPPAD_BOOSTVECTOR 0 - -/*! -\def CPPAD_CPPADVECTOR -If this symbol is one, -we are using CppAD vector for CPPAD_TESTVECTOR. -It this symbol is zero, -we are not using CppAD vector for CPPAD_TESTVECTOR. -*/ -# define CPPAD_CPPADVECTOR 1 - -/*! -\def CPPAD_STDVECTOR -If this symbol is one, -we are using standard vector for CPPAD_TESTVECTOR. -It this symbol is zero, -we are not using standard vector for CPPAD_TESTVECTOR. -*/ -# define CPPAD_STDVECTOR 0 - -/*! -\def CPPAD_EIGENVECTOR -If this symbol is one, -we are using Eigen vector for CPPAD_TESTVECTOR. -If this symbol is zero, -we are not using Eigen vector for CPPAD_TESTVECTOR. -*/ -# define CPPAD_EIGENVECTOR 0 - -/*! -\def CPPAD_HAS_GETTIMEOFDAY -If this symbol is one, and _MSC_VER is not defined, -this system supports the gettimeofday funcgtion. -Otherwise, this smybol should be zero. -*/ -# define CPPAD_HAS_GETTIMEOFDAY 1 - -/*! -\def CPPAD_SIZE_T_NOT_UNSIGNED_INT -If this symbol is zero, the type size_t is the same as the type unsigned int, -otherwise this symbol is one. -*/ -# define CPPAD_SIZE_T_NOT_UNSIGNED_INT 1 - -/*! -\def CPPAD_TAPE_ADDR_TYPE -Is the type used to store address on the tape. If not size_t, then -sizeof(CPPAD_TAPE_ADDR_TYPE) <= sizeof( size_t ) -to conserve memory. -This type must support \c std::numeric_limits, -the \c <= operator, -and conversion to \c size_t. -Make sure that the type chosen returns true for is_pod -in pod_vector.hpp. -This type is later defined as \c addr_t in the CppAD namespace. -*/ -# define CPPAD_TAPE_ADDR_TYPE unsigned int - -/*! -\def CPPAD_TAPE_ID_TYPE -Is the type used to store tape identifiers. If not size_t, then -sizeof(CPPAD_TAPE_ID_TYPE) <= sizeof( size_t ) -to conserve memory. -This type must support \c std::numeric_limits, -the \c <= operator, -and conversion to \c size_t. -Make sure that the type chosen returns true for is_pod -in pod_vector.hpp. -This type is later defined as \c tape_id_t in the CppAD namespace. -*/ -# define CPPAD_TAPE_ID_TYPE unsigned int - -/*! -\def CPPAD_MAX_NUM_THREADS -Specifies the maximum number of threads that CppAD can support -(must be greater than or equal four). - -The user may define CPPAD_MAX_NUM_THREADS before including any of the CppAD -header files. If it is not yet defined, -*/ -# ifndef CPPAD_MAX_NUM_THREADS -# define CPPAD_MAX_NUM_THREADS 48 -# endif - -/*! -\def CPPAD_HAS_MKSTEMP -It true, mkstemp works in C++ on this system. -*/ -# define CPPAD_HAS_MKSTEMP 1 - -/*! -\def CPPAD_HAS_TMPNAM_S -It true, tmpnam_s works in C++ on this system. -*/ -# define CPPAD_HAS_TMPNAM_S 0 - -// --------------------------------------------------------------------------- -// defines that only depend on values above -// --------------------------------------------------------------------------- -/*! -\def CPPAD_NULL -This preprocessor symbol is used for a null pointer. - -If it is not yet defined, -it is defined when cppad/local/define.hpp is included. -*/ -# ifndef CPPAD_NULL -# if CPPAD_USE_CPLUSPLUS_2011 -# define CPPAD_NULL nullptr -# else -# define CPPAD_NULL 0 -# endif -# endif - -# endif diff --git a/ct_core/include/ct/external/cppad/core/abort_recording.hpp b/ct_core/include/ct/external/cppad/core/abort_recording.hpp deleted file mode 100644 index a1a088550..000000000 --- a/ct_core/include/ct/external/cppad/core/abort_recording.hpp +++ /dev/null @@ -1,61 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_ABORT_RECORDING_HPP -# define CPPAD_CORE_ABORT_RECORDING_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin abort_recording$$ -$spell -$$ - -$section Abort Recording of an Operation Sequence$$ -$mindex tape$$ - - -$head Syntax$$ -$codei%AD<%Base%>::abort_recording()%$$ - -$head Purpose$$ -Sometimes it is necessary to abort the recording of an operation sequence -that started with a call of the form -$codei% - Independent(%x%) -%$$ -If such a recording is currently in progress, -$code abort_recording$$ will stop the recording and delete the -corresponding information. -Otherwise, $code abort_recording$$ has no effect. - -$children% - example/abort_recording.cpp -%$$ -$head Example$$ -The file -$cref abort_recording.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ----------------------------------------------------------------------------- -*/ - - -namespace CppAD { - template - void AD::abort_recording(void) - { local::ADTape* tape = AD::tape_ptr(); - if( tape != CPPAD_NULL ) - AD::tape_manage(tape_manage_delete); - } -} - -# endif diff --git a/ct_core/include/ct/external/cppad/core/abs.hpp b/ct_core/include/ct/external/cppad/core/abs.hpp deleted file mode 100644 index 1e3fadb8a..000000000 --- a/ct_core/include/ct/external/cppad/core/abs.hpp +++ /dev/null @@ -1,114 +0,0 @@ -# ifndef CPPAD_CORE_ABS_HPP -# define CPPAD_CORE_ABS_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-17 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin abs$$ -$spell - fabs - Vec - std - faq - Taylor - Cpp - namespace - const - abs -$$ - -$section AD Absolute Value Functions: abs, fabs$$ - -$head Syntax$$ -$icode%y% = abs(%x%) -%$$ -$icode%y% = fabs(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -In the case where $icode x$$ is an AD type, -this is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Complex Types$$ -The functions $code abs$$ and $icode fabs$$ -are not defined for the base types -$code std::complex$$ or $code std::complex$$ -because the complex $code abs$$ function is not complex differentiable -(see $cref/complex types faq/Faq/Complex Types/$$). - -$head Derivative$$ -CppAD defines the derivative of the $code abs$$ function is -the $cref sign$$ function; i.e., -$latex \[ -{\rm abs}^{(1)} ( x ) = {\rm sign} (x ) = -\left\{ \begin{array}{rl} - +1 & {\rm if} \; x > 0 \\ - 0 & {\rm if} \; x = 0 \\ - -1 & {\rm if} \; x < 0 -\end{array} \right. -\] $$ -The result for $icode%x% == 0%$$ used to be a directional derivative. - -$head Example$$ -$children% - example/fabs.cpp -%$$ -The file -$cref fabs.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD AD::abs_me (void) const -{ - AD result; - result.value_ = abs(value_); - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - if( Variable(*this) ) - { // add this operation to the tape - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::AbsOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::AbsOp) == 1 ); - local::ADTape *tape = tape_this(); - - // corresponding operand address - tape->Rec_.PutArg(taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::AbsOp); - // make result a variable - result.tape_id_ = tape->id_; - } - return result; -} - -template -inline AD abs(const AD &x) -{ return x.abs_me(); } - -template -inline AD abs(const VecAD_reference &x) -{ return x.ADBase().abs_me(); } - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/acosh.hpp b/ct_core/include/ct/external/cppad/core/acosh.hpp deleted file mode 100644 index 5c4bc1563..000000000 --- a/ct_core/include/ct/external/cppad/core/acosh.hpp +++ /dev/null @@ -1,96 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_ACOSH_HPP -# define CPPAD_CORE_ACOSH_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin acosh$$ -$spell - acosh - const - Vec - std - cmath - CppAD -$$ -$section The Inverse Hyperbolic Cosine Function: acosh$$ - -$head Syntax$$ -$icode%y% = acosh(%x%)%$$ - -$head Description$$ -The inverse hyperbolic cosine function is defined by -$icode%x% == cosh(%y%)%$$. - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head CPPAD_USE_CPLUSPLUS_2011$$ - -$subhead true$$ -If this preprocessor symbol is true ($code 1$$), -and $icode x$$ is an AD type, -this is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$subhead false$$ -If this preprocessor symbol is false ($code 0$$), -CppAD uses the representation -$latex \[ -\R{acosh} (x) = \log \left( x + \sqrt{ x^2 - 1 } \right) -\] $$ -to compute this function. - -$head Example$$ -$children% - example/acosh.cpp -%$$ -The file -$cref acosh.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ -# include -# if ! CPPAD_USE_CPLUSPLUS_2011 - -// BEGIN CppAD namespace -namespace CppAD { - -template -Type acosh_template(const Type &x) -{ return CppAD::log( x + CppAD::sqrt( x * x - Type(1) ) ); -} - -inline float acosh(const float &x) -{ return acosh_template(x); } - -inline double acosh(const double &x) -{ return acosh_template(x); } - -template -inline AD acosh(const AD &x) -{ return acosh_template(x); } - -template -inline AD acosh(const VecAD_reference &x) -{ return acosh_template( x.ADBase() ); } - - -} // END CppAD namespace - -# endif // CPPAD_USE_CPLUSPLUS_2011 -# endif // CPPAD_ACOSH_INCLUDED diff --git a/ct_core/include/ct/external/cppad/core/ad.hpp b/ct_core/include/ct/external/cppad/core/ad.hpp deleted file mode 100644 index adf34c8eb..000000000 --- a/ct_core/include/ct/external/cppad/core/ad.hpp +++ /dev/null @@ -1,298 +0,0 @@ -# ifndef CPPAD_CORE_AD_HPP -# define CPPAD_CORE_AD_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-17 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// simple AD operations that must be defined for AD as well as base class -# include -# include - -// define the template classes that are used by the AD template class -# include -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -typedef enum { - tape_manage_new, - tape_manage_delete, - tape_manage_clear -} tape_manage_job; - -template -class AD { -private : -public: - // ----------------------------------------------------------------------- - // value_ corresponding to this object - Base value_; - - // Tape identifier corresponding to taddr - tape_id_t tape_id_; - - // taddr_ in tape for this variable - addr_t taddr_; - // ----------------------------------------------------------------------- -private: - - // enable use of AD in parallel mode - template - friend void parallel_ad(void); - - // template friend functions where template parameter is not bound - template - friend void Independent(VectorAD &x, size_t abort_op_index); - - // one argument functions - friend bool Parameter - (const AD &u); - friend bool Parameter - (const VecAD &u); - friend bool Variable - (const AD &u); - friend bool Variable - (const VecAD &u); - friend int Integer - (const AD &u); - friend AD Var2Par - (const AD &u); - - // power function - friend AD pow - (const AD &x, const AD &y); - - // azmul function - friend AD azmul - (const AD &x, const AD &y); - - // order determining functions, see ordered.hpp - friend bool GreaterThanZero (const AD &x); - friend bool GreaterThanOrZero (const AD &x); - friend bool LessThanZero (const AD &x); - friend bool LessThanOrZero (const AD &x); - friend bool abs_geq - (const AD& x, const AD& y); - - // The identical property functions, see identical.hpp - friend bool IdenticalPar (const AD &x); - friend bool IdenticalZero (const AD &x); - friend bool IdenticalOne (const AD &x); - friend bool IdenticalEqualPar - (const AD &x, const AD &y); - - // EqualOpSeq function - friend bool EqualOpSeq - (const AD &u, const AD &v); - - // NearEqual function - friend bool NearEqual ( - const AD &x, const AD &y, const Base &r, const Base &a); - - friend bool NearEqual ( - const Base &x, const AD &y, const Base &r, const Base &a); - - friend bool NearEqual ( - const AD &x, const Base &y, const Base &r, const Base &a); - - // CondExp function - friend AD CondExpOp ( - enum CompareOp cop , - const AD &left , - const AD &right , - const AD &trueCase , - const AD &falseCase - ); - - // classes - friend class local::ADTape; - friend class ADFun; - friend class atomic_base; - friend class discrete; - friend class VecAD; - friend class VecAD_reference; - - // arithematic binary operators - friend AD operator + - (const AD &left, const AD &right); - friend AD operator - - (const AD &left, const AD &right); - friend AD operator * - (const AD &left, const AD &right); - friend AD operator / - (const AD &left, const AD &right); - - // comparison operators - friend bool operator < - (const AD &left, const AD &right); - friend bool operator <= - (const AD &left, const AD &right); - friend bool operator > - (const AD &left, const AD &right); - friend bool operator >= - (const AD &left, const AD &right); - friend bool operator == - (const AD &left, const AD &right); - friend bool operator != - (const AD &left, const AD &right); - - // input operator - friend std::istream& operator >> - (std::istream &is, AD &x); - - // output operations - friend std::ostream& operator << - (std::ostream &os, const AD &x); - friend void PrintFor ( - const AD& flag , - const char* before , - const AD& var , - const char* after - ); -public: - // type of value - typedef Base value_type; - - // implicit default constructor - inline AD(void); - - // use default implicit copy constructor and assignment operator - // inline AD(const AD &x); - // inline AD& operator=(const AD &x); - - // implicit construction and assingment from base type - inline AD(const Base &b); - inline AD& operator=(const Base &b); - - // implicit contructor and assignment from VecAD::reference - inline AD(const VecAD_reference &x); - inline AD& operator=(const VecAD_reference &x); - -# if CPPAD_DEPRECATED - // implicit construction from some other type (depricated) - template inline AD(const T &t); -# else - // explicit construction from some other type (depricated) - template inline explicit AD(const T &t); -# endif - - // assignment from some other type - template inline AD& operator=(const T &right); - - // base type corresponding to an AD object - friend Base Value (const AD &x); - - // compound assignment operators - inline AD& operator += (const AD &right); - inline AD& operator -= (const AD &right); - inline AD& operator *= (const AD &right); - inline AD& operator /= (const AD &right); - - // unary operators - inline AD operator +(void) const; - inline AD operator -(void) const; - - // destructor - ~AD(void) - { } - - // interface so these functions need not be friends - inline AD abs_me(void) const; - inline AD acos_me(void) const; - inline AD asin_me(void) const; - inline AD atan_me(void) const; - inline AD cos_me(void) const; - inline AD cosh_me(void) const; - inline AD exp_me(void) const; - inline AD fabs_me(void) const; - inline AD log_me(void) const; - inline AD sin_me(void) const; - inline AD sign_me(void) const; - inline AD sinh_me(void) const; - inline AD sqrt_me(void) const; - inline AD tan_me(void) const; - inline AD tanh_me(void) const; -# if CPPAD_USE_CPLUSPLUS_2011 - inline AD erf_me(void) const; - inline AD asinh_me(void) const; - inline AD acosh_me(void) const; - inline AD atanh_me(void) const; - inline AD expm1_me(void) const; - inline AD log1p_me(void) const; -# endif - - // ---------------------------------------------------------- - // static public member functions - - // abort current AD recording - static void abort_recording(void); - - // set the maximum number of OpenMP threads (deprecated) - static void omp_max_thread(size_t number); - - // These functions declared public so can be accessed by user through - // a macro interface and are not intended for direct use. - // The macro interface is documented in bool_fun.hpp. - // Developer documentation for these fucntions is in bool_fun.hpp - static inline bool UnaryBool( - bool FunName(const Base &x), - const AD &x - ); - static inline bool BinaryBool( - bool FunName(const Base &x, const Base &y), - const AD &x , const AD &y - ); - -private: - // - // Make this variable a parameter - // - void make_parameter(void) - { CPPAD_ASSERT_UNKNOWN( Variable(*this) ); // currently a var - tape_id_ = 0; - } - // - // Make this parameter a new variable - // - void make_variable(size_t id, size_t taddr) - { CPPAD_ASSERT_UNKNOWN( Parameter(*this) ); // currently a par - CPPAD_ASSERT_UNKNOWN( taddr > 0 ); // sure valid taddr - - taddr_ = taddr; - tape_id_ = id; - } - // --------------------------------------------------------------- - // tape linking functions - // - // not static - inline local::ADTape* tape_this(void) const; - // - // static - inline static tape_id_t** tape_id_handle(size_t thread); - inline static tape_id_t* tape_id_ptr(size_t thread); - inline static local::ADTape** tape_handle(size_t thread); - static local::ADTape* tape_manage(tape_manage_job job); - inline static local::ADTape* tape_ptr(void); - inline static local::ADTape* tape_ptr(tape_id_t tape_id); -}; -// --------------------------------------------------------------------------- - -} // END_CPPAD_NAMESPACE - -// tape linking private functions -# include - -// operations that expect the AD template class to be defined - - -# endif diff --git a/ct_core/include/ct/external/cppad/core/ad_assign.hpp b/ct_core/include/ct/external/cppad/core/ad_assign.hpp deleted file mode 100644 index ba252e2af..000000000 --- a/ct_core/include/ct/external/cppad/core/ad_assign.hpp +++ /dev/null @@ -1,141 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_AD_ASSIGN_HPP -# define CPPAD_CORE_AD_ASSIGN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ------------------------------------------------------------------------------- - -$begin ad_assign$$ -$spell - Vec - const -$$ - - -$section AD Assignment Operator$$ -$mindex assign Base VecAD$$ - -$head Syntax$$ -$icode%y% = %x%$$ - -$head Purpose$$ -Assigns the value in $icode x$$ to the object $icode y$$. -In either case, - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Type% &%x% -%$$ -where $icode Type$$ is -$codei%VecAD<%Base%>::reference%$$, -$codei%AD<%Base%>%$$, -$icode Base$$, -or any type that has an implicit constructor of the form -$icode%Base%(%x%)%$$. - -$head y$$ -The target $icode y$$ has prototype -$codei% - AD<%Base%> %y% -%$$ - -$head Example$$ -$children% - example/ad_assign.cpp -%$$ -The file $cref ad_assign.cpp$$ contain examples and tests of these operations. -It test returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------- -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -/*! -\file ad_assign.hpp -AD constructors and and copy operations. -*/ - -/*! -\page AD_default_assign -Use default assignment operator -because they may be optimized better than the code below: -\code -template -inline AD& AD::operator=(const AD &right) -{ value_ = right.value_; - tape_id_ = right.tape_id_; - taddr_ = right.taddr_; - - return *this; -} -\endcode -*/ - -/*! -Assignment to Base type value. - -\tparam Base -Base type for this AD object. - -\param b -is the Base type value being assignment to this AD object. -The tape identifier will be an invalid tape identifier, -so this object is initially a parameter. -*/ -template -inline AD& AD::operator=(const Base &b) -{ value_ = b; - tape_id_ = 0; - - // check that this is a parameter - CPPAD_ASSERT_UNKNOWN( Parameter(*this) ); - - return *this; -} - -/*! -Assignment to an ADVec element drops the vector information. - -\tparam Base -Base type for this AD object. -*/ -template -inline AD& AD::operator=(const VecAD_reference &x) -{ return *this = x.ADBase(); } - -/*! -Assignment from any other type, converts to Base type, and then uses assignment -from Base type. - -\tparam Base -Base type for this AD object. - -\tparam T -is the the type that is being assigned to AD. -There must be an assignment for Base from Type. - -\param t -is the object that is being assigned to an AD object. -*/ -template -template -inline AD& AD::operator=(const T &t) -{ return *this = Base(t); } - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/ad_binary.hpp b/ct_core/include/ct/external/cppad/core/ad_binary.hpp deleted file mode 100644 index fac06d319..000000000 --- a/ct_core/include/ct/external/cppad/core/ad_binary.hpp +++ /dev/null @@ -1,145 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_AD_BINARY_HPP -# define CPPAD_CORE_AD_BINARY_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin ad_binary$$ -$spell - Op - VecAD - const -$$ - -$section AD Binary Arithmetic Operators$$ -$mindex + add plus - subtract minus * multiply times / divide$$ - - - - - - - -$head Syntax$$ -$icode%z% = %x% %Op% %y%$$ - -$head Purpose$$ -Performs arithmetic operations where either $icode x$$ or $icode y$$ -has type -$codei%AD<%Base%>%$$ or -$cref%VecAD::reference%VecAD%VecAD::reference%$$. - -$head Op$$ -The operator $icode Op$$ is one of the following -$table -$bold Op$$ $cnext $bold Meaning$$ $rnext -$code +$$ $cnext $icode z$$ is $icode x$$ plus $icode y$$ $rnext -$code -$$ $cnext $icode z$$ is $icode x$$ minus $icode y$$ $rnext -$code *$$ $cnext $icode z$$ is $icode x$$ times $icode y$$ $rnext -$code /$$ $cnext $icode z$$ is $icode x$$ divided by $icode y$$ -$tend - -$head Base$$ -The type $icode Base$$ is determined by the operand that -has type $codei%AD<%Base%>%$$ or $codei%VecAD<%Base%>::reference%$$. - -$head x$$ -The operand $icode x$$ has the following prototype -$codei% - const %Type% &%x% -%$$ -where $icode Type$$ is -$codei%VecAD<%Base%>::reference%$$, -$codei%AD<%Base%>%$$, -$icode Base$$, or -$code double$$. - -$head y$$ -The operand $icode y$$ has the following prototype -$codei% - const %Type% &%y% -%$$ -where $icode Type$$ is -$codei%VecAD<%Base%>::reference%$$, -$codei%AD<%Base%>%$$, -$icode Base$$, or -$code double$$. - - -$head z$$ -The result $icode z$$ has the following prototype -$codei% - %Type% %z% -%$$ -where $icode Type$$ is -$codei%AD<%Base%>%$$. - -$head Operation Sequence$$ -This is an $cref/atomic/glossary/Operation/Atomic/$$ -$cref/AD of Base/glossary/AD of Base/$$ operation -and hence it is part of the current -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$children% - example/add.cpp% - example/sub.cpp% - example/mul.cpp% - example/div.cpp -%$$ - -$head Example$$ -The following files contain examples and tests of these functions. -Each test returns true if it succeeds and false otherwise. -$table -$rref add.cpp$$ -$rref sub.cpp$$ -$rref mul.cpp$$ -$rref div.cpp$$ -$tend - -$head Derivative$$ -If $latex f$$ and $latex g$$ are -$cref/Base functions/glossary/Base Function/$$ - -$subhead Addition$$ -$latex \[ - \D{[ f(x) + g(x) ]}{x} = \D{f(x)}{x} + \D{g(x)}{x} -\] $$ - -$subhead Subtraction$$ -$latex \[ - \D{[ f(x) - g(x) ]}{x} = \D{f(x)}{x} - \D{g(x)}{x} -\] $$ - -$subhead Multiplication$$ -$latex \[ - \D{[ f(x) * g(x) ]}{x} = g(x) * \D{f(x)}{x} + f(x) * \D{g(x)}{x} -\] $$ - -$subhead Division$$ -$latex \[ - \D{[ f(x) / g(x) ]}{x} = - [1/g(x)] * \D{f(x)}{x} - [f(x)/g(x)^2] * \D{g(x)}{x} -\] $$ - -$end ------------------------------------------------------------------------------ -*/ -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/core/ad_ctor.hpp b/ct_core/include/ct/external/cppad/core/ad_ctor.hpp deleted file mode 100644 index 35f9406c7..000000000 --- a/ct_core/include/ct/external/cppad/core/ad_ctor.hpp +++ /dev/null @@ -1,178 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_AD_CTOR_HPP -# define CPPAD_CORE_AD_CTOR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ------------------------------------------------------------------------------- - -$begin ad_ctor$$ -$spell - cppad - ctor - initializes - Vec - const -$$ - - -$section AD Constructors $$ -$mindex convert Base VecAD$$ - -$head Syntax$$ -$codei%AD<%Base%> %y%() -%$$ -$codei%AD<%Base%> %y%(%x%) -%$$ - -$head Purpose$$ -creates a new $codei%AD<%Base%>%$$ object $icode y$$ -and initializes its value as equal to $icode x$$. - -$head x$$ - -$subhead implicit$$ -There is an implicit constructor where $icode x$$ has one of the following -prototypes: -$codei% - const %Base%& %x% - const VecAD<%Base%>& %x% -%$$ - -$subhead explicit$$ -There is an explicit constructor where $icode x$$ has prototype -$codei% - const %Type%& %x% -%$$ -for any type that has an explicit constructor of the form -$icode%Base%(%x%)%$$. - -$subhead Deprecated 2013-12-31$$ -If you set $cref/cppad_deprecated/cmake/cppad_deprecated/$$ -to be $code YES$$ during the install procedure, -you will get an implicit constructor with prototype -$codei% - const %Type%& %x% -%$$ -for any type that has an explicit constructor of the form -$icode%Base%(%x%)%$$. - -$head y$$ -The target $icode y$$ has prototype -$codei% - AD<%Base%> %y% -%$$ - -$head Example$$ -$children% - example/ad_ctor.cpp -%$$ -The files $cref ad_ctor.cpp$$ contain examples and tests of these operations. -It test returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------- -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -/*! -\file ad_ctor.hpp -AD constructors and and copy operations. -*/ - -/*! -\page AD_default_ctor -Use default copy constructor -because they may be optimized better than the code below: -\code -template -inline AD::AD(const AD &x) -{ - value_ = x.value_; - tape_id_ = x.tape_id_; - taddr_ = x.taddr_; - - return; -} -\endcode -*/ - -/*! -Default Constructor. - -\tparam Base -Base type for this AD object. -*/ -template -inline AD::AD(void) -: value_() -, tape_id_(0) -, taddr_(0) -{ } - - -/*! -Constructor from Base type. - -\tparam Base -Base type for this AD object. - -\param b -is the Base type value corresponding to this AD object. -The tape identifier will be an invalid tape identifier, -so this object is initially a parameter. -*/ -template -inline AD::AD(const Base &b) -: value_(b) -, tape_id_(0) -, taddr_(0) -{ // check that this is a parameter - CPPAD_ASSERT_UNKNOWN( Parameter(*this) ); -} - -/*! -Constructor from an ADVec element drops the vector information. - -\tparam Base -Base type for this AD object. -*/ -template -inline AD::AD(const VecAD_reference &x) -{ *this = x.ADBase(); } - -/*! -Constructor from any other type, converts to Base type, and uses constructor -from Base type. - -\tparam Base -Base type for this AD object. - -\tparam T -is the the type that is being converted to AD. -There must be a constructor for Base from Type. - -\param t -is the object that is being converted from T to AD. -*/ -template -template -inline AD::AD(const T &t) -: value_(Base(t)) -, tape_id_(0) -, taddr_(0) -{ } - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/ad_fun.hpp b/ct_core/include/ct/external/cppad/core/ad_fun.hpp deleted file mode 100644 index f1855e0b9..000000000 --- a/ct_core/include/ct/external/cppad/core/ad_fun.hpp +++ /dev/null @@ -1,657 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_AD_FUN_HPP -# define CPPAD_CORE_AD_FUN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin ADFun$$ -$spell - xk - Ind - bool - taylor_ - sizeof - const - std - ind_taddr_ - dep_taddr_ -$$ - -$spell -$$ - -$section ADFun Objects$$ - - -$head Purpose$$ -An AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$ -is stored in an $code ADFun$$ object by its $cref FunConstruct$$. -The $code ADFun$$ object can then be used to calculate function values, -derivative values, and other values related to the corresponding function. - -$childtable% - cppad/core/independent.hpp% - cppad/core/fun_construct.hpp% - cppad/core/dependent.hpp% - cppad/core/abort_recording.hpp% - omh/seq_property.omh% - cppad/core/fun_eval.hpp% - cppad/core/drivers.hpp% - cppad/core/fun_check.hpp% - cppad/core/optimize.hpp% - cppad/core/check_for_nan.hpp -%$$ - -$end -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file ad_fun.hpp -File used to define the ADFun class. -*/ - -/*! -Class used to hold function objects - -\tparam Base -A function object has a recording of AD operations. -It does it calculations using \c Base operations. -*/ - -template -class ADFun { -// ------------------------------------------------------------ -// Private member variables -private: - /// Has this ADFun object been optmized - bool has_been_optimized_; - - /// Check for nan's and report message to user (default value is true). - bool check_for_nan_; - - /// If zero, ignoring comparison operators. Otherwise is the - /// compare change count at which to store the operator index. - size_t compare_change_count_; - - /// If compare_change_count_ is zero, compare_change_number_ is also zero. - /// Otherwise, it is set to the number of comparison operations that had a - /// different result during the subsequent zero order forward. - size_t compare_change_number_; - - /// If compare_change_count is zero, compare_change_op_index_ is also - /// zero. Otherwise it is the operator index for the comparison operator - //// that corresponded to the number changing from count-1 to count. - size_t compare_change_op_index_; - - /// number of orders stored in taylor_ - size_t num_order_taylor_; - - /// maximum number of orders that will fit in taylor_ - size_t cap_order_taylor_; - - /// number of directions stored in taylor_ - size_t num_direction_taylor_; - - /// number of variables in the recording (play_) - size_t num_var_tape_; - - /// tape address for the independent variables - CppAD::vector ind_taddr_; - - /// tape address and parameter flag for the dependent variables - CppAD::vector dep_taddr_; - - /// which dependent variables are actually parameters - CppAD::vector dep_parameter_; - - /// results of the forward mode calculations - local::pod_vector taylor_; - - /// which operations can be conditionally skipped - /// Set during forward pass of order zero - local::pod_vector cskip_op_; - - /// Variable on the tape corresponding to each vecad load operation - /// (if zero, the operation corresponds to a parameter). - local::pod_vector load_op_; - - /// the operation sequence corresponding to this object - local::player play_; - - /// Packed results of the forward mode Jacobian sparsity calculations. - /// for_jac_sparse_pack_.n_set() != 0 implies other sparsity results - /// are empty - local::sparse_pack for_jac_sparse_pack_; - - /// Set results of the forward mode Jacobian sparsity calculations - /// for_jac_sparse_set_.n_set() != 0 implies for_sparse_pack_ is empty. - local::sparse_list for_jac_sparse_set_; - -// ------------------------------------------------------------ -// Private member functions - - /// change the operation sequence corresponding to this object - template - void Dependent(local::ADTape *tape, const ADvector &y); - - // ------------------------------------------------------------ - // vector of bool version of ForSparseJac - // (see doxygen in for_sparse_jac.hpp) - template - void ForSparseJacCase( - bool set_type , - bool transpose , - bool dependency, - size_t q , - const VectorSet& r , - VectorSet& s - ); - // vector of std::set version of ForSparseJac - // (see doxygen in for_sparse_jac.hpp) - template - void ForSparseJacCase( - const std::set& set_type , - bool transpose , - bool dependency, - size_t q , - const VectorSet& r , - VectorSet& s - ); - // ------------------------------------------------------------ - // vector of bool version of RevSparseJac - // (see doxygen in rev_sparse_jac.hpp) - template - void RevSparseJacCase( - bool set_type , - bool transpose , - bool dependency, - size_t p , - const VectorSet& s , - VectorSet& r - ); - // vector of std::set version of RevSparseJac - // (see doxygen in rev_sparse_jac.hpp) - template - void RevSparseJacCase( - const std::set& set_type , - bool transpose , - bool dependency, - size_t p , - const VectorSet& s , - VectorSet& r - ); - // ------------------------------------------------------------ - // vector of bool version of ForSparseHes - // (see doxygen in rev_sparse_hes.hpp) - template - void ForSparseHesCase( - bool set_type , - const VectorSet& r , - const VectorSet& s , - VectorSet& h - ); - // vector of std::set version of ForSparseHes - // (see doxygen in rev_sparse_hes.hpp) - template - void ForSparseHesCase( - const std::set& set_type , - const VectorSet& r , - const VectorSet& s , - VectorSet& h - ); - // ------------------------------------------------------------ - // vector of bool version of RevSparseHes - // (see doxygen in rev_sparse_hes.hpp) - template - void RevSparseHesCase( - bool set_type , - bool transpose , - size_t q , - const VectorSet& s , - VectorSet& h - ); - // vector of std::set version of RevSparseHes - // (see doxygen in rev_sparse_hes.hpp) - template - void RevSparseHesCase( - const std::set& set_type , - bool transpose , - size_t q , - const VectorSet& s , - VectorSet& h - ); - // ------------------------------------------------------------ - // Forward mode version of SparseJacobian - // (see doxygen in sparse_jacobian.hpp) - template - size_t SparseJacobianFor( - const VectorBase& x , - VectorSet& p_transpose , - const VectorSize& row , - const VectorSize& col , - VectorBase& jac , - sparse_jacobian_work& work - ); - // Reverse mode version of SparseJacobian - // (see doxygen in sparse_jacobian.hpp) - template - size_t SparseJacobianRev( - const VectorBase& x , - VectorSet& p , - const VectorSize& row , - const VectorSize& col , - VectorBase& jac , - sparse_jacobian_work& work - ); - // ------------------------------------------------------------ - // combined sparse_list and sparse_pack version of - // SparseHessian (see doxygen in sparse_hessian.hpp) - template - size_t SparseHessianCompute( - const VectorBase& x , - const VectorBase& w , - VectorSet& sparsity , - const VectorSize& row , - const VectorSize& col , - VectorBase& hes , - sparse_hessian_work& work - ); -// ------------------------------------------------------------ -public: - /// copy constructor - ADFun(const ADFun& g) - : num_var_tape_(0) - { CppAD::ErrorHandler::Call( - true, - __LINE__, - __FILE__, - "ADFun(const ADFun& g)", - "Attempting to use the ADFun copy constructor.\n" - "Perhaps you are passing an ADFun object " - "by value instead of by reference." - ); - } - - /// default constructor - ADFun(void); - - // assignment operator - // (see doxygen in fun_construct.hpp) - void operator=(const ADFun& f); - - /// sequence constructor - template - ADFun(const ADvector &x, const ADvector &y); - - /// destructor - ~ADFun(void) - { } - - /// set value of check_for_nan_ - void check_for_nan(bool value) - { check_for_nan_ = value; } - bool check_for_nan(void) const - { return check_for_nan_; } - - /// assign a new operation sequence - template - void Dependent(const ADvector &x, const ADvector &y); - - /// forward mode user API, one order multiple directions. - template - VectorBase Forward(size_t q, size_t r, const VectorBase& x); - - /// forward mode user API, multiple directions one order. - template - VectorBase Forward(size_t q, - const VectorBase& x, std::ostream& s = std::cout - ); - - /// reverse mode sweep - template - VectorBase Reverse(size_t p, const VectorBase &v); - - // forward mode Jacobian sparsity - // (see doxygen documentation in for_sparse_jac.hpp) - template - VectorSet ForSparseJac( - size_t q, const VectorSet &r, bool transpose = false, - bool dependency = false - ); - // reverse mode Jacobian sparsity - // (see doxygen documentation in rev_sparse_jac.hpp) - template - VectorSet RevSparseJac( - size_t q, const VectorSet &s, bool transpose = false, - bool dependency = false - ); - // forward mode Hessian sparsity - // (see doxygen documentation in rev_sparse_hes.hpp) - template - VectorSet ForSparseHes( - const VectorSet &r, const VectorSet &s - ); - // internal set sparsity version of ForSparseHes - // (used by checkpoint functions only) - void ForSparseHesCheckpoint( - vector& r , - vector& s , - local::sparse_list& h - ); - // reverse mode Hessian sparsity - // (see doxygen documentation in rev_sparse_hes.hpp) - template - VectorSet RevSparseHes( - size_t q, const VectorSet &s, bool transpose = false - ); - // internal set sparsity version of RevSparseHes - // (used by checkpoint functions only) - void RevSparseHesCheckpoint( - size_t q , - vector& s , - bool transpose , - local::sparse_list& h - ); - // internal set sparsity version of RevSparseJac - // (used by checkpoint functions only) - void RevSparseJacCheckpoint( - size_t q , - const local::sparse_list& r , - bool transpose , - bool dependency , - local::sparse_list& s - ); - // internal set sparsity version of RevSparseJac - // (used by checkpoint functions only) - void ForSparseJacCheckpoint( - size_t q , - const local::sparse_list& r , - bool transpose , - bool dependency , - local::sparse_list& s - ); - - /// amount of memory used for Jacobain sparsity pattern - size_t size_forward_bool(void) const - { return for_jac_sparse_pack_.memory(); } - - /// free memory used for Jacobain sparsity pattern - void size_forward_bool(size_t zero) - { CPPAD_ASSERT_KNOWN( - zero == 0, - "size_forward_bool: argument not equal to zero" - ); - for_jac_sparse_pack_.resize(0, 0); - } - - /// total number of elements used for Jacobian sparsity pattern - size_t size_forward_set(void) const - { return for_jac_sparse_set_.number_elements(); } - - /// free memory used for Jacobain sparsity pattern - void size_forward_set(size_t zero) - { CPPAD_ASSERT_KNOWN( - zero == 0, - "size_forward_bool: argument not equal to zero" - ); - for_jac_sparse_set_.resize(0, 0); - } - - /// number of operators in the operation sequence - size_t size_op(void) const - { return play_.num_op_rec(); } - - /// number of operator arguments in the operation sequence - size_t size_op_arg(void) const - { return play_.num_op_arg_rec(); } - - /// amount of memory required for the operation sequence - size_t size_op_seq(void) const - { return play_.Memory(); } - - /// number of parameters in the operation sequence - size_t size_par(void) const - { return play_.num_par_rec(); } - - /// number taylor coefficient orders calculated - size_t size_order(void) const - { return num_order_taylor_; } - - /// number taylor coefficient directions calculated - size_t size_direction(void) const - { return num_direction_taylor_; } - - /// number of characters in the operation sequence - size_t size_text(void) const - { return play_.num_text_rec(); } - - /// number of variables in opertion sequence - size_t size_var(void) const - { return num_var_tape_; } - - /// number of VecAD indices in the operation sequence - size_t size_VecAD(void) const - { return play_.num_vec_ind_rec(); } - - /// set number of orders currently allocated (user API) - void capacity_order(size_t c); - - /// set number of orders and directions currently allocated - void capacity_order(size_t c, size_t r); - - /// number of variables in conditional expressions that can be skipped - size_t number_skip(void); - - /// number of independent variables - size_t Domain(void) const - { return ind_taddr_.size(); } - - /// number of dependent variables - size_t Range(void) const - { return dep_taddr_.size(); } - - /// is variable a parameter - bool Parameter(size_t i) - { CPPAD_ASSERT_KNOWN( - i < dep_taddr_.size(), - "Argument to Parameter is >= dimension of range space" - ); - return dep_parameter_[i]; - } - - /// Deprecated: number of comparison operations that changed - /// for the previous zero order forward (than when function was recorded) - size_t CompareChange(void) const - { return compare_change_number_; } - - /// count as which to store operator index - void compare_change_count(size_t count) - { compare_change_count_ = count; - compare_change_number_ = 0; - compare_change_op_index_ = 0; - } - - /// number of comparison operations that changed - size_t compare_change_number(void) const - { return compare_change_number_; } - - /// operator index for the count-th comparison change - size_t compare_change_op_index(void) const - { if( has_been_optimized_ ) - return 0; - return compare_change_op_index_; - } - - /// calculate entire Jacobian - template - VectorBase Jacobian(const VectorBase &x); - - /// calculate Hessian for one component of f - template - VectorBase Hessian(const VectorBase &x, const VectorBase &w); - template - VectorBase Hessian(const VectorBase &x, size_t i); - - /// forward mode calculation of partial w.r.t one domain component - template - VectorBase ForOne( - const VectorBase &x , - size_t j ); - - /// reverse mode calculation of derivative of one range component - template - VectorBase RevOne( - const VectorBase &x , - size_t i ); - - /// forward mode calculation of a subset of second order partials - template - VectorBase ForTwo( - const VectorBase &x , - const VectorSize_t &J , - const VectorSize_t &K ); - - /// reverse mode calculation of a subset of second order partials - template - VectorBase RevTwo( - const VectorBase &x , - const VectorSize_t &I , - const VectorSize_t &J ); - - /// calculate sparse Jacobians - template - VectorBase SparseJacobian( - const VectorBase &x - ); - template - VectorBase SparseJacobian( - const VectorBase &x , - const VectorSet &p - ); - template - size_t SparseJacobianForward( - const VectorBase& x , - const VectorSet& p , - const VectorSize& r , - const VectorSize& c , - VectorBase& jac , - sparse_jacobian_work& work - ); - template - size_t SparseJacobianReverse( - const VectorBase& x , - const VectorSet& p , - const VectorSize& r , - const VectorSize& c , - VectorBase& jac , - sparse_jacobian_work& work - ); - - /// calculate sparse Hessians - template - VectorBase SparseHessian( - const VectorBase& x , - const VectorBase& w - ); - template - VectorBase SparseHessian( - const VectorBase& x , - const VectorBase& w , - const VectorBool& p - ); - template - size_t SparseHessian( - const VectorBase& x , - const VectorBase& w , - const VectorSet& p , - const VectorSize& r , - const VectorSize& c , - VectorBase& hes , - sparse_hessian_work& work - ); - - // Optimize the tape - // (see doxygen documentation in optimize.hpp) - void optimize( const std::string& options = "" ); - // ------------------- Deprecated ----------------------------- - - /// deprecated: assign a new operation sequence - template - void Dependent(const ADvector &y); - - /// Deprecated: number of variables in opertion sequence - size_t Size(void) const - { return num_var_tape_; } - - /// Deprecated: # taylor_ coefficients currently stored - /// (per variable,direction) - size_t Order(void) const - { return num_order_taylor_ - 1; } - - /// Deprecated: amount of memory for this object - /// Note that an approximation is used for the std::set memory - size_t Memory(void) const - { size_t pervar = cap_order_taylor_ * sizeof(Base) - + for_jac_sparse_pack_.memory() - + 3 * sizeof(size_t) * for_jac_sparse_set_.number_elements(); - size_t total = num_var_tape_ * pervar + play_.Memory(); - return total; - } - - /// Deprecated: # taylor_ coefficient orderss stored - /// (per variable,direction) - size_t taylor_size(void) const - { return num_order_taylor_; } - - /// Deprecated: Does this AD operation sequence use - /// VecAD::reference operands - bool use_VecAD(void) const - { return play_.num_vec_ind_rec() > 0; } - - /// Deprecated: # taylor_ coefficient orders calculated - /// (per variable,direction) - size_t size_taylor(void) const - { return num_order_taylor_; } - - /// Deprecated: set number of orders currently allocated - /// (per variable,direction) - void capacity_taylor(size_t per_var); -}; -// --------------------------------------------------------------------------- - -} // END_CPPAD_NAMESPACE - -// non-user interfaces -# include -# include -# include -# include -# include -# include -# include -# include - -// user interfaces -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/core/ad_io.hpp b/ct_core/include/ct/external/cppad/core/ad_io.hpp deleted file mode 100644 index 9dd00d2eb..000000000 --- a/ct_core/include/ct/external/cppad/core/ad_io.hpp +++ /dev/null @@ -1,224 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_AD_IO_HPP -# define CPPAD_CORE_AD_IO_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin ad_input$$ -$spell - VecAD - std - istream - const -$$ - - -$section AD Output Stream Operator$$ -$mindex >> input write$$ - -$head Syntax$$ -$icode%is% >> %x%$$ - - -$head Purpose$$ -Sets $icode x$$ to a $cref/parameter/glossary/Parameter/$$ -with value $icode b$$ corresponding to -$codei% - %is% >> %b% -%$$ -where $icode b$$ is a $icode Base$$ object. -It is assumed that this $icode Base$$ input operation returns -a reference to $icode is$$. - -$head is$$ -The operand $icode is$$ has prototype -$codei% - std::istream& %is% -%$$ - -$head x$$ -The operand $icode x$$ has one of the following prototypes -$codei% - AD<%Base%>& %x% -%$$ - -$head Result$$ -The result of this operation can be used as a reference to $icode is$$. -For example, if the operand $icode y$$ has prototype -$codei% - AD<%Base%> %y% -%$$ -then the syntax -$codei% - %is% >> %x% >> %y% -%$$ -will first read the $icode Base$$ value of $icode x$$ from $icode is$$, -and then read the $icode Base$$ value to $icode y$$. - -$head Operation Sequence$$ -The result of this operation is not an -$cref/AD of Base/glossary/AD of Base/$$ object. -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Example$$ -$children% - example/ad_input.cpp -%$$ -The file -$cref ad_input.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------- -$begin ad_output$$ -$spell - VecAD - std - ostream - const -$$ - - -$section AD Output Stream Operator$$ -$mindex <<$$ - -$head Syntax$$ -$icode%os% << %x%$$ - - -$head Purpose$$ -Writes the $icode Base$$ value, corresponding to $icode x$$, -to the output stream $icode os$$. - -$head Assumption$$ -If $icode b$$ is a $icode Base$$ object, -$codei% - %os% << %b% -%$$ -returns a reference to $icode os$$. - -$head os$$ -The operand $icode os$$ has prototype -$codei% - std::ostream& %os% -%$$ - -$head x$$ -The operand $icode x$$ has one of the following prototypes -$codei% - const AD<%Base%>& %x% - const VecAD<%Base%>::reference& %x% -%$$ - -$head Result$$ -The result of this operation can be used as a reference to $icode os$$. -For example, if the operand $icode y$$ has prototype -$codei% - AD<%Base%> %y% -%$$ -then the syntax -$codei% - %os% << %x% << %y% -%$$ -will output the value corresponding to $icode x$$ -followed by the value corresponding to $icode y$$. - -$head Operation Sequence$$ -The result of this operation is not an -$cref/AD of Base/glossary/AD of Base/$$ object. -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Example$$ -$children% - example/ad_output.cpp -%$$ -The file -$cref ad_output.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------- -*/ -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file ad_io.hpp -AD input and ouput stream operators. -*/ -// --------------------------------------------------------------------------- -/*! -Read an AD object from an input stream. - -\tparam Base -Base type for the AD object. - -\param is [in,out] -Is the input stream from which that value is read. - -\param x [out] -is the object that is being set to a value. -Upone return, x.value_ is read from the input stream -and x.tape_is_ is zero; i.e., x is a parameter. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -std::istream& operator >> (std::istream& is, AD& x) -{ // like assignment to a base type value - x.tape_id_ = 0; - CPPAD_ASSERT_UNKNOWN( Parameter(x) ); - return (is >> x.value_); -} -// --------------------------------------------------------------------------- -/*! -Write an AD object to an output stream. - -\tparam Base -Base type for the AD object. - -\param os [in,out] -Is the output stream to which that value is written. - -\param x -is the object that is being written to the output stream. -This is equivalent to writing x.value_ to the output stream. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -std::ostream& operator << (std::ostream &os, const AD &x) -{ return (os << x.value_); } -// --------------------------------------------------------------------------- -/*! -Write a VecAD_reference object to an output stream. - -\tparam Base -Base type for the VecAD_reference object. - -\param os [in,out] -Is the output stream to which that value is written. - -\param x -is the element of the VecAD object that is being written to the output stream. -This is equivalent to writing the corresponing Base value to the stream. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -std::ostream& operator << (std::ostream &os, const VecAD_reference &x) -{ return (os << x.ADBase()); } - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/ad_to_string.hpp b/ct_core/include/ct/external/cppad/core/ad_to_string.hpp deleted file mode 100644 index dc431b1c0..000000000 --- a/ct_core/include/ct/external/cppad/core/ad_to_string.hpp +++ /dev/null @@ -1,71 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_AD_TO_STRING_HPP -# define CPPAD_CORE_AD_TO_STRING_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin ad_to_string$$ -$spell - const - std -$$ - -$section Convert An AD or Base Type to String$$ - -$head Syntax$$ -$icode%s% = to_string(%value%)%$$. - -$head See Also$$ -$cref to_string$$, $cref base_to_string$$ - -$head value$$ -The argument $icode value$$ has prototype -$codei% - const AD<%Base%>& %value% - const %Base%& %value% -%$$ -where $icode Base$$ is a type that supports the -$cref base_to_string$$ type requirement. - -$head s$$ -The return value has prototype -$codei% - std::string %s% -%$$ -and contains a representation of the specified $icode value$$. -If $icode value$$ is an AD type, -the result has the same precision as for the $icode Base$$ type. - -$head Example$$ -The file $cref to_string.cpp$$ -includes an example and test of $code to_string$$ with AD types. -It returns true if it succeeds and false otherwise. - -$end -*/ -# include -# include - -namespace CppAD { - - // Template definition is in cppad/utility/to_string.hpp. - // Partial specialzation for AD types - template - struct to_string_struct< CppAD::AD > - { std::string operator()(const CppAD::AD& value) - { to_string_struct ts; - return ts( Value( Var2Par( value ) ) ); } - }; - -} - -# endif diff --git a/ct_core/include/ct/external/cppad/core/ad_valued.hpp b/ct_core/include/ct/external/cppad/core/ad_valued.hpp deleted file mode 100644 index 810703822..000000000 --- a/ct_core/include/ct/external/cppad/core/ad_valued.hpp +++ /dev/null @@ -1,49 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_AD_VALUED_HPP -# define CPPAD_CORE_AD_VALUED_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin ADValued$$ -$spell -$$ - - -$section AD Valued Operations and Functions$$ - -$comment atomic.omh includes atomic_base.omh which atomic_base.hpp$$ -$childtable% - cppad/core/arithmetic.hpp% - cppad/core/standard_math.hpp% - cppad/core/cond_exp.hpp% - cppad/core/discrete.hpp% - cppad/core/numeric_limits.hpp% - omh/atomic.omh -%$$ - -$end -*/ - -// include MathOther.h after CondExp.h because some MathOther.h routines use -// CondExp.h and CondExp.h is not sufficently declared in Declare.h - -# include -# include -# include -# include -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/core/add.hpp b/ct_core/include/ct/external/cppad/core/add.hpp deleted file mode 100644 index ad15e36b1..000000000 --- a/ct_core/include/ct/external/cppad/core/add.hpp +++ /dev/null @@ -1,97 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_ADD_HPP -# define CPPAD_CORE_ADD_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD operator + (const AD &left , const AD &right) -{ - // compute the Base part of this AD object - AD result; - result.value_ = left.value_ + right.value_; - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - // check if there is a recording in progress - local::ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return result; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = left.tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // result = variable + variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::AddvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::AddvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(left.taddr_, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::AddvvOp); - // make result a variable - result.tape_id_ = tape_id; - } - else if( IdenticalZero(right.value_) ) - { // result = variable + 0 - result.make_variable(left.tape_id_, left.taddr_); - } - else - { // result = variable + parameter - // = parameter + variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::AddpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::AddpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(p, left.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::AddpvOp); - // make result a variable - result.tape_id_ = tape_id; - } - } - else if( var_right ) - { if( IdenticalZero(left.value_) ) - { // result = 0 + variable - result.make_variable(right.tape_id_, right.taddr_); - } - else - { // result = parameter + variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::AddpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::AddpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left.value_); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::AddpvOp); - // make result a variable - result.tape_id_ = tape_id; - } - } - return result; -} - -// convert other cases into the case above -CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR(+) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/add_eq.hpp b/ct_core/include/ct/external/cppad/core/add_eq.hpp deleted file mode 100644 index dc22c0969..000000000 --- a/ct_core/include/ct/external/cppad/core/add_eq.hpp +++ /dev/null @@ -1,92 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_ADD_EQ_HPP -# define CPPAD_CORE_ADD_EQ_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD& AD::operator += (const AD &right) -{ - // compute the Base part - Base left; - left = value_; - value_ += right.value_; - - // check if there is a recording in progress - local::ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return *this; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // this = variable + variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::AddvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::AddvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(taddr_, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(local::AddvvOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - else if( ! IdenticalZero( right.value_ ) ) - { // this = variable + parameter - // = parameter + variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::AddpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::AddpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(p, taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(local::AddpvOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - } - else if( var_right ) - { if( IdenticalZero(left) ) - { // this = 0 + right - make_variable(right.tape_id_, right.taddr_); - } - else - { // this = parameter + variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::AddpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::AddpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(local::AddpvOp); - // make this a variable - tape_id_ = tape_id; - } - } - return *this; -} - -CPPAD_FOLD_ASSIGNMENT_OPERATOR(+=) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/arithmetic.hpp b/ct_core/include/ct/external/cppad/core/arithmetic.hpp deleted file mode 100644 index e1b3fe3de..000000000 --- a/ct_core/include/ct/external/cppad/core/arithmetic.hpp +++ /dev/null @@ -1,42 +0,0 @@ -# ifndef CPPAD_CORE_ARITHMETIC_HPP -# define CPPAD_CORE_ARITHMETIC_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-17 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin Arithmetic$$ -$spell - Op - const -$$ - - - -$section AD Arithmetic Operators and Compound Assignments$$ - -$childtable% - cppad/core/unary_plus.hpp% - cppad/core/unary_minus.hpp% - cppad/core/ad_binary.hpp% - cppad/core/compound_assign.hpp -%$$ - -$end -------------------------------------------------------------------------------- -*/ -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/core/asinh.hpp b/ct_core/include/ct/external/cppad/core/asinh.hpp deleted file mode 100644 index d3f4aa22d..000000000 --- a/ct_core/include/ct/external/cppad/core/asinh.hpp +++ /dev/null @@ -1,97 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_ASINH_HPP -# define CPPAD_CORE_ASINH_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- - -$begin asinh$$ -$spell - asinh - const - Vec - std - cmath - CppAD -$$ -$section The Inverse Hyperbolic Sine Function: asinh$$ - -$head Syntax$$ -$icode%y% = asinh(%x%)%$$ - -$head Description$$ -The inverse hyperbolic sine function is defined by -$icode%x% == sinh(%y%)%$$. - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head CPPAD_USE_CPLUSPLUS_2011$$ - -$subhead true$$ -If this preprocessor symbol is true ($code 1$$), -and $icode x$$ is an AD type, -this is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$subhead false$$ -If this preprocessor symbol is false ($code 0$$), -CppAD uses the representation -$latex \[ -\R{asinh} (x) = \log \left( x + \sqrt{ 1 + x^2 } \right) -\] $$ -to compute this function. - -$head Example$$ -$children% - example/asinh.cpp -%$$ -The file -$cref asinh.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ -# include -# if ! CPPAD_USE_CPLUSPLUS_2011 - -// BEGIN CppAD namespace -namespace CppAD { - -template -Type asinh_template(const Type &x) -{ return CppAD::log( x + CppAD::sqrt( Type(1) + x * x ) ); -} - -inline float asinh(const float &x) -{ return asinh_template(x); } - -inline double asinh(const double &x) -{ return asinh_template(x); } - -template -inline AD asinh(const AD &x) -{ return asinh_template(x); } - -template -inline AD asinh(const VecAD_reference &x) -{ return asinh_template( x.ADBase() ); } - - -} // END CppAD namespace - -# endif // CPPAD_USE_CPLUSPLUS_2011 -# endif // CPPAD_ASINH_INCLUDED diff --git a/ct_core/include/ct/external/cppad/core/atan2.hpp b/ct_core/include/ct/external/cppad/core/atan2.hpp deleted file mode 100644 index e1e4317b1..000000000 --- a/ct_core/include/ct/external/cppad/core/atan2.hpp +++ /dev/null @@ -1,141 +0,0 @@ -# ifndef CPPAD_CORE_ATAN2_HPP -# define CPPAD_CORE_ATAN2_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-17 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin atan2$$ -$spell - Vec - CppAD - namespace - std - atan - const -$$ - - -$section AD Two Argument Inverse Tangent Function$$ -$mindex tan atan2$$ - -$head Syntax$$ -$icode%theta% = atan2(%y%, %x%)%$$ - - -$head Purpose$$ -Determines an angle $latex \theta \in [ - \pi , + \pi ]$$ -such that -$latex \[ -\begin{array}{rcl} - \sin ( \theta ) & = & y / \sqrt{ x^2 + y^2 } \\ - \cos ( \theta ) & = & x / \sqrt{ x^2 + y^2 } -\end{array} -\] $$ - -$head y$$ -The argument $icode y$$ has one of the following prototypes -$codei% - const AD<%Base%> &%y% - const VecAD<%Base%>::reference &%y% -%$$ - -$head x$$ -The argument $icode x$$ has one of the following prototypes -$codei% - const AD<%Base%> &%x% - const VecAD<%Base%>::reference &%x% -%$$ - -$head theta$$ -The result $icode theta$$ has prototype -$codei% - AD<%Base%> %theta% -%$$ - -$head Operation Sequence$$ -The AD of $icode Base$$ -operation sequence used to calculate $icode theta$$ is -$cref/independent/glossary/Operation/Independent/$$ -of $icode x$$ and $icode y$$. - -$head Example$$ -$children% - example/atan2.cpp -%$$ -The file -$cref atan2.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ - -namespace CppAD { // BEGIN CppAD namespace - -inline float atan2(float x, float y) -{ return std::atan2(x, y); } - -inline double atan2(double x, double y) -{ return std::atan2(x, y); } - -// The code below is used as an example by the CondExp documentation. -// BEGIN CondExp -template -AD atan2 (const AD &y, const AD &x) -{ AD alpha; - AD beta; - AD theta; - - AD zero(0.); - AD pi2(2. * atan(1.)); - AD pi(2. * pi2); - - AD ax = fabs(x); - AD ay = fabs(y); - - // if( ax > ay ) - // theta = atan(ay / ax); - // else theta = pi2 - atan(ax / ay); - alpha = atan(ay / ax); - beta = pi2 - atan(ax / ay); - theta = CondExpGt(ax, ay, alpha, beta); // use of CondExp - - // if( x <= 0 ) - // theta = pi - theta; - theta = CondExpLe(x, zero, pi - theta, theta); // use of CondExp - - // if( y <= 0 ) - // theta = - theta; - theta = CondExpLe(y, zero, -theta, theta); // use of CondExp - - return theta; -} -// END CondExp - -template -inline AD atan2 (const VecAD_reference &y, const AD &x) -{ return atan2( y.ADBase() , x ); } - -template -inline AD atan2 (const AD &y, const VecAD_reference &x) -{ return atan2( y , x.ADBase() ); } - -template -inline AD atan2 -(const VecAD_reference &y, const VecAD_reference &x) -{ return atan2( y.ADBase() , x.ADBase() ); } - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/atanh.hpp b/ct_core/include/ct/external/cppad/core/atanh.hpp deleted file mode 100644 index d9b3d3372..000000000 --- a/ct_core/include/ct/external/cppad/core/atanh.hpp +++ /dev/null @@ -1,97 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_ATANH_HPP -# define CPPAD_CORE_ATANH_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin atanh$$ -$spell - atanh - const - Vec - std - cmath - CppAD - tanh -$$ -$section The Inverse Hyperbolic Tangent Function: atanh$$ - -$head Syntax$$ -$icode%y% = atanh(%x%)%$$ - -$head Description$$ -The inverse hyperbolic tangent function is defined by -$icode%x% == tanh(%y%)%$$. - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head CPPAD_USE_CPLUSPLUS_2011$$ - -$subhead true$$ -If this preprocessor symbol is true ($code 1$$), -and $icode x$$ is an AD type, -this is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$subhead false$$ -If this preprocessor symbol is false ($code 0$$), -CppAD uses the representation -$latex \[ -\R{atanh} (x) = \frac{1}{2} \log \left( \frac{1 + x}{1 - x} \right) -\] $$ -to compute this function. - -$head Example$$ -$children% - example/atanh.cpp -%$$ -The file -$cref atanh.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ -# include -# if ! CPPAD_USE_CPLUSPLUS_2011 - -// BEGIN CppAD namespace -namespace CppAD { - -template -Type atanh_template(const Type &x) -{ return CppAD::log( (Type(1) + x) / (Type(1) - x) ) / Type(2); -} - -inline float atanh(const float &x) -{ return atanh_template(x); } - -inline double atanh(const double &x) -{ return atanh_template(x); } - -template -inline AD atanh(const AD &x) -{ return atanh_template(x); } - -template -inline AD atanh(const VecAD_reference &x) -{ return atanh_template( x.ADBase() ); } - - -} // END CppAD namespace - -# endif // CPPAD_USE_CPLUSPLUS_2011 -# endif // CPPAD_ATANH_INCLUDED diff --git a/ct_core/include/ct/external/cppad/core/atomic_base.hpp b/ct_core/include/ct/external/cppad/core/atomic_base.hpp deleted file mode 100644 index 1d9c50ed2..000000000 --- a/ct_core/include/ct/external/cppad/core/atomic_base.hpp +++ /dev/null @@ -1,1853 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_ATOMIC_BASE_HPP -# define CPPAD_CORE_ATOMIC_BASE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include -# include -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file atomic_base.hpp -Base class for atomic user operations. -*/ - -template -class atomic_base { -// =================================================================== -public: - enum option_enum { - pack_sparsity_enum , - bool_sparsity_enum , - set_sparsity_enum - }; -private: - // ------------------------------------------------------ - // constants - // - /// index of this object in class_object - const size_t index_; - - // ----------------------------------------------------- - // variables - // - /// sparsity pattern this object is currently using - /// (set by constructor and option member functions) - option_enum sparsity_; - - /// temporary work space used afun, declared here to avoid memory - /// allocation/deallocation for each call to afun - vector afun_vx_[CPPAD_MAX_NUM_THREADS]; - vector afun_vy_[CPPAD_MAX_NUM_THREADS]; - vector afun_tx_[CPPAD_MAX_NUM_THREADS]; - vector afun_ty_[CPPAD_MAX_NUM_THREADS]; - - // ----------------------------------------------------- - // static member functions - // - /// List of all the object in this class - static std::vector& class_object(void) - { CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static std::vector list_; - return list_; - } - /// List of names for each object in this class - static std::vector& class_name(void) - { CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static std::vector list_; - return list_; - } - // ===================================================================== -public: - // ----------------------------------------------------- - // member functions not in user API - // - /// current sparsity setting - option_enum sparsity(void) const - { return sparsity_; } - - /// Name corresponding to a base_atomic object - const std::string& afun_name(void) const - { return class_name()[index_]; } -/* -$begin atomic_ctor$$ -$spell - enum - sq - std - afun - arg - CppAD - bool - ctor - const - mat_mul_xam.cpp - hpp -$$ - -$section Atomic Function Constructor$$ - -$head Syntax$$ -$icode%atomic_user afun%(%ctor_arg_list%) -%$$ -$codei%atomic_base<%Base%>(%name%, %sparsity%) -%$$ - -$head atomic_user$$ - -$subhead ctor_arg_list$$ -Is a list of arguments for the $icode atomic_user$$ constructor. - -$subhead afun$$ -The object $icode afun$$ must stay in scope for as long -as the corresponding atomic function is used. -This includes use by any $cref/ADFun/ADFun/$$ that -has this $icode atomic_user$$ operation in its -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$subhead Implementation$$ -The user defined $icode atomic_user$$ class is a publicly derived class of -$codei%atomic_base<%Base%>%$$. -It should be declared as follows: -$codei% - class %atomic_user% : public CppAD::atomic_base<%Base%> { - public: - %atomic_user%(%ctor_arg_list%) : atomic_base<%Base%>(%name%, %sparsity%) - %...% - }; -%$$ -where $icode ...$$ -denotes the rest of the implementation of the derived class. -This includes completing the constructor and -all the virtual functions that have their -$code atomic_base$$ implementations replaced by -$icode atomic_user$$ implementations. - -$head atomic_base$$ - -$subhead Restrictions$$ -The $code atomic_base$$ constructor cannot be called in -$cref/parallel/ta_in_parallel/$$ mode. - -$subhead Base$$ -The template parameter determines the -$icode Base$$ type for this $codei%AD<%Base%>%$$ atomic operation. - -$subhead name$$ -This $code atomic_base$$ constructor argument has the following prototype -$codei% - const std::string& %name% -%$$ -It is the name for this atomic function and is used for error reporting. -The suggested value for $icode name$$ is $icode afun$$ or $icode atomic_user$$, -i.e., the name of the corresponding atomic object or class. - -$subhead sparsity$$ -This $code atomic_base$$ constructor argument has prototype -$codei% - atomic_base<%Base%>::option_enum %sparsity% -%$$ -The current $icode sparsity$$ for an $code atomic_base$$ object -determines which type of sparsity patterns it uses -and its value is one of the following: -$table -$icode sparsity$$ $cnext sparsity patterns $rnext -$codei%atomic_base<%Base%>::pack_sparsity_enum%$$ $pre $$ $cnext - $cref/vectorBool/CppAD_vector/vectorBool/$$ -$rnext -$codei%atomic_base<%Base%>::bool_sparsity_enum%$$ $pre $$ $cnext - $cref/vector/CppAD_vector/$$$code $$ -$rnext -$codei%atomic_base<%Base%>::set_sparsity_enum%$$ $pre $$ $cnext - $cref/vector/CppAD_vector/$$$code >$$ -$tend -There is a default value for $icode sparsity$$ if it is not -included in the constructor (which may be either the bool or set option). - -$head Example$$ - -$subhead Define Constructor$$ -The following is an example of a user atomic function constructor definitions: -$cref%get_started.cpp%atomic_get_started.cpp%Constructor%$$. - -$subhead Use Constructor$$ -The following is an example using a user atomic function constructor: -$cref%get_started.cpp%atomic_get_started.cpp%Use Atomic Function%Constructor%$$. - -$end -*/ -/*! -Base class for atomic_user functions. - -\tparam Base -This class is used for defining an AD atomic operation y = f(x). -*/ -/// make sure user does not invoke the default constructor -atomic_base(void) -{ CPPAD_ASSERT_KNOWN(false, - "Attempt to use the atomic_base default constructor" - ); -} -/*! -Constructor - -\param name -name used for error reporting - -\param sparsity [in] -what type of sparsity patterns are computed by this function, -bool_sparsity_enum or set_sparsity_enum. Default value is -bool sparsity patterns. -*/ -atomic_base( - const std::string& name, - option_enum sparsity = bool_sparsity_enum -) : -index_( class_object().size() ) , -sparsity_( sparsity ) -{ CPPAD_ASSERT_KNOWN( - ! thread_alloc::in_parallel() , - "atomic_base: constructor cannot be called in parallel mode." - ); - class_object().push_back(this); - class_name().push_back(name); - CPPAD_ASSERT_UNKNOWN( class_object().size() == class_name().size() ); -} -/// destructor informs CppAD that this atomic function with this index -/// has dropped out of scope by setting its pointer to null -virtual ~atomic_base(void) -{ CPPAD_ASSERT_UNKNOWN( class_object().size() > index_ ); - // change object pointer to null, but leave name for error reporting - class_object()[index_] = CPPAD_NULL; -} -/// atomic_base function object corresponding to a certain index -static atomic_base* class_object(size_t index) -{ CPPAD_ASSERT_UNKNOWN( class_object().size() > index ); - return class_object()[index]; -} -/// atomic_base function name corresponding to a certain index -static const std::string& class_name(size_t index) -{ CPPAD_ASSERT_UNKNOWN( class_name().size() > index ); - return class_name()[index]; -} -/* -$begin atomic_option$$ -$spell - sq - enum - afun - bool - CppAD - std - typedef -$$ - -$section Set Atomic Function Options$$ - -$head Syntax$$ -$icode%afun%.option(%option_value%)%$$ -These settings do not apply to individual $icode afun$$ calls, -but rather all subsequent uses of the corresponding atomic operation -in an $cref ADFun$$ object. - -$head atomic_sparsity$$ -Note that, if you use $cref optimize$$, these sparsity patterns are used -to determine the $cref/dependency/dependency.cpp/$$ relationship between -argument and result variables. - -$subhead pack_sparsity_enum$$ -If $icode option_value$$ is $codei%atomic_base<%Base%>::pack_sparsity_enum%$$, -then the type used by $icode afun$$ for -$cref/sparsity patterns/glossary/Sparsity Pattern/$$, -(after the option is set) will be -$codei% - typedef CppAD::vectorBool %atomic_sparsity% -%$$ -If $icode r$$ is a sparsity pattern -for a matrix $latex R \in B^{p \times q}$$: -$icode%r%.size() == %p% * %q%$$. - -$subhead bool_sparsity_enum$$ -If $icode option_value$$ is $codei%atomic_base<%Base%>::bool_sparsity_enum%$$, -then the type used by $icode afun$$ for -$cref/sparsity patterns/glossary/Sparsity Pattern/$$, -(after the option is set) will be -$codei% - typedef CppAD::vector %atomic_sparsity% -%$$ -If $icode r$$ is a sparsity pattern -for a matrix $latex R \in B^{p \times q}$$: -$icode%r%.size() == %p% * %q%$$. - -$subhead set_sparsity_enum$$ -If $icode option_value$$ is $icode%atomic_base<%Base%>::set_sparsity_enum%$$, -then the type used by $icode afun$$ for -$cref/sparsity patterns/glossary/Sparsity Pattern/$$, -(after the option is set) will be -$codei% - typedef CppAD::vector< std::set > %atomic_sparsity% -%$$ -If $icode r$$ is a sparsity pattern -for a matrix $latex R \in B^{p \times q}$$: -$icode%r%.size() == %p%$$, and for $latex i = 0 , \ldots , p-1$$, -the elements of $icode%r%[%i%]%$$ are between zero and $latex q-1$$ inclusive. - -$end -*/ -void option(enum option_enum option_value) -{ switch( option_value ) - { case pack_sparsity_enum: - case bool_sparsity_enum: - case set_sparsity_enum: - sparsity_ = option_value; - break; - - default: - CPPAD_ASSERT_KNOWN( - false, - "atoic_base::option: option_value is not valid" - ); - } - return; -} -/* ------------------------------------------------------------------------------ -$begin atomic_afun$$ - -$spell - sq - mul - afun - const - CppAD - mat_mul.cpp -$$ - -$section Using AD Version of Atomic Function$$ - -$head Syntax$$ -$icode%afun%(%ax%, %ay%)%$$ - -$head Purpose$$ -Given $icode ax$$, -this call computes the corresponding value of $icode ay$$. -If $codei%AD<%Base%>%$$ operations are being recorded, -it enters the computation as an atomic operation in the recording; -see $cref/start recording/Independent/Start Recording/$$. - -$head ADVector$$ -The type $icode ADVector$$ must be a -$cref/simple vector class/SimpleVector/$$ with elements of type -$codei%AD<%Base%>%$$; see $cref/Base/atomic_ctor/atomic_base/Base/$$. - -$head afun$$ -is a $cref/atomic_user/atomic_ctor/atomic_user/$$ object -and this $icode afun$$ function call is implemented by the -$cref/atomic_base/atomic_ctor/atomic_base/$$ class. - -$head ax$$ -This argument has prototype -$codei% - const %ADVector%& %ax% -%$$ -and size must be equal to $icode n$$. -It specifies vector $latex x \in B^n$$ -at which an $codei%AD<%Base%>%$$ version of -$latex y = f(x)$$ is to be evaluated; see -$cref/Base/atomic_ctor/atomic_base/Base/$$. - -$head ay$$ -This argument has prototype -$codei% - %ADVector%& %ay% -%$$ -and size must be equal to $icode m$$. -The input values of its elements -are not specified (must not matter). -Upon return, it is an $codei%AD<%Base%>%$$ version of -$latex y = f(x)$$. - -$head Examples$$ -The following files contain example uses of -the AD version of atomic functions during recording: -$cref%get_started.cpp%atomic_get_started.cpp%Use Atomic Function%Recording%$$, -$cref%norm_sq.cpp%atomic_norm_sq.cpp%Use Atomic Function%Recording%$$, -$cref%reciprocal.cpp%atomic_reciprocal.cpp%Use Atomic Function%Recording%$$, -$cref%tangent.cpp%atomic_tangent.cpp%Use Atomic Function%Recording%$$, -$cref%mat_mul.cpp%atomic_mat_mul.cpp%Use Atomic Function%Recording%$$. - -$end ------------------------------------------------------------------------------ -*/ -/*! -Implement the user call to afun(ax, ay) and old_atomic call to -afun(ax, ay, id). - -\tparam ADVector -A simple vector class with elements of type AD. - -\param id -optional extra information vector that is just passed through by CppAD, -and used by old_atomic derived class (not other derived classes). -This is an extra parameter to the virtual callbacks for old_atomic; -see the set_old member function. - -\param ax -is the argument vector for this call, -ax.size() determines the number of arguments. - -\param ay -is the result vector for this call, -ay.size() determines the number of results. -*/ -template -void operator()( - const ADVector& ax , - ADVector& ay , - size_t id = 0 ) -{ size_t i, j; - size_t n = ax.size(); - size_t m = ay.size(); -# ifndef NDEBUG - bool ok; - std::string msg = "atomic_base: " + afun_name() + ".eval: "; - if( (n == 0) | (m == 0) ) - { msg += "ax.size() or ay.size() is zero"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - size_t thread = thread_alloc::thread_num(); - vector & tx = afun_tx_[thread]; - vector & ty = afun_ty_[thread]; - vector & vx = afun_vx_[thread]; - vector & vy = afun_vy_[thread]; - // - if( vx.size() != n ) - { vx.resize(n); - tx.resize(n); - } - if( vy.size() != m ) - { vy.resize(m); - ty.resize(m); - } - // - // Determine tape corresponding to variables in ax - tape_id_t tape_id = 0; - local::ADTape* tape = CPPAD_NULL; - for(j = 0; j < n; j++) - { tx[j] = ax[j].value_; - vx[j] = Variable( ax[j] ); - if( vx[j] ) - { - if( tape_id == 0 ) - { tape = ax[j].tape_this(); - tape_id = ax[j].tape_id_; - CPPAD_ASSERT_UNKNOWN( tape != CPPAD_NULL ); - } -# ifndef NDEBUG - if( tape_id != ax[j].tape_id_ ) - { msg += afun_name() + - ": ax contains variables from different threads."; - CPPAD_ASSERT_KNOWN(false, msg.c_str()); - } -# endif - } - } - // Use zero order forward mode to compute values - size_t p = 0, q = 0; - set_old(id); -# ifdef NDEBUG - forward(p, q, vx, vy, tx, ty); -# else - ok = forward(p, q, vx, vy, tx, ty); - if( ! ok ) - { msg += afun_name() + ": ok is false for " - "zero order forward mode calculation."; - CPPAD_ASSERT_KNOWN(false, msg.c_str()); - } -# endif - bool record_operation = false; - for(i = 0; i < m; i++) - { - // pass back values - ay[i].value_ = ty[i]; - - // initialize entire vector parameters (not in tape) - ay[i].tape_id_ = 0; - ay[i].taddr_ = 0; - - // we need to record this operation if - // any of the eleemnts of ay are variables, - record_operation |= vy[i]; - } -# ifndef NDEBUG - if( record_operation & (tape == CPPAD_NULL) ) - { msg += - "all elements of vx are false but vy contains a true element"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - // if tape is not null, ay is on the tape - if( record_operation ) - { - // Operator that marks beginning of this atomic operation - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::UserOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::UserOp) == 4 ); - tape->Rec_.PutArg(index_, id, n, m); - tape->Rec_.PutOp(local::UserOp); - - // Now put n operators, one for each element of argument vector - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::UsravOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::UsrapOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::UsravOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::UsrapOp) == 1 ); - for(j = 0; j < n; j++) - { if( vx[j] ) - { // information for an argument that is a variable - tape->Rec_.PutArg(ax[j].taddr_); - tape->Rec_.PutOp(local::UsravOp); - } - else - { // information for an argument that is parameter - addr_t par = tape->Rec_.PutPar(ax[j].value_); - tape->Rec_.PutArg(par); - tape->Rec_.PutOp(local::UsrapOp); - } - } - - // Now put m operators, one for each element of result vector - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::UsrrpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::UsrrpOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::UsrrvOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::UsrrvOp) == 1 ); - for(i = 0; i < m; i++) - { if( vy[i] ) - { ay[i].taddr_ = tape->Rec_.PutOp(local::UsrrvOp); - ay[i].tape_id_ = tape_id; - } - else - { addr_t par = tape->Rec_.PutPar(ay[i].value_); - tape->Rec_.PutArg(par); - tape->Rec_.PutOp(local::UsrrpOp); - } - } - - // Put a duplicate UserOp at end of UserOp sequence - tape->Rec_.PutArg(index_, id, n, m); - tape->Rec_.PutOp(local::UserOp); - } - return; -} -/* ------------------------------------------------------------------------------ -$begin atomic_forward$$ -$spell - sq - mul.hpp - hes - afun - vx - vy - ty - Taylor - const - CppAD - bool -$$ - -$section Atomic Forward Mode$$ -$mindex callback virtual$$ - - -$head Syntax$$ -$icode%ok% = %afun%.forward(%p%, %q%, %vx%, %vy%, %tx%, %ty%)%$$ - -$head Purpose$$ -This virtual function is used by $cref atomic_afun$$ -to evaluate function values. -It is also used buy $cref/forward/Forward/$$ -to compute function vales and derivatives. - -$head Implementation$$ -This virtual function must be defined by the -$cref/atomic_user/atomic_ctor/atomic_user/$$ class. -It can just return $icode%ok% == false%$$ -(and not compute anything) for values -of $icode%q% > 0%$$ that are greater than those used by your -$cref/forward/Forward/$$ mode calculations. - -$head p$$ -The argument $icode p$$ has prototype -$codei% - size_t %p% -%$$ -It specifies the lowest order Taylor coefficient that we are evaluating. -During calls to $cref atomic_afun$$, $icode%p% == 0%$$. - -$head q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the highest order Taylor coefficient that we are evaluating. -During calls to $cref atomic_afun$$, $icode%q% == 0%$$. - -$head vx$$ -The $code forward$$ argument $icode vx$$ has prototype -$codei% - const CppAD::vector& %vx% -%$$ -The case $icode%vx%.size() > 0%$$ only occurs while evaluating a call to -$cref atomic_afun$$. -In this case, -$icode%p% == %q% == 0%$$, -$icode%vx%.size() == %n%$$, and -for $latex j = 0 , \ldots , n-1$$, -$icode%vx%[%j%]%$$ is true if and only if -$icode%ax%[%j%]%$$ is a $cref/variable/glossary/Variable/$$ -in the corresponding call to -$codei% - %afun%(%ax%, %ay%) -%$$ -If $icode%vx%.size() == 0%$$, -then $icode%vy%.size() == 0%$$ and neither of these vectors -should be used. - -$head vy$$ -The $code forward$$ argument $icode vy$$ has prototype -$codei% - CppAD::vector& %vy% -%$$ -If $icode%vy%.size() == 0%$$, it should not be used. -Otherwise, -$icode%q% == 0%$$ and $icode%vy%.size() == %m%$$. -The input values of the elements of $icode vy$$ -are not specified (must not matter). -Upon return, for $latex j = 0 , \ldots , m-1$$, -$icode%vy%[%i%]%$$ is true if and only if -$icode%ay%[%i%]%$$ is a variable -(CppAD uses $icode vy$$ to reduce the necessary computations). - -$head tx$$ -The argument $icode tx$$ has prototype -$codei% - const CppAD::vector<%Base%>& %tx% -%$$ -and $icode%tx%.size() == (%q%+1)*%n%$$. -For $latex j = 0 , \ldots , n-1$$ and $latex k = 0 , \ldots , q$$, -we use the Taylor coefficient notation -$latex \[ -\begin{array}{rcl} - x_j^k & = & tx [ j * ( q + 1 ) + k ] - \\ - X_j (t) & = & x_j^0 + x_j^1 t^1 + \cdots + x_j^q t^q -\end{array} -\] $$ -Note that superscripts represent an index for $latex x_j^k$$ -and an exponent for $latex t^k$$. -Also note that the Taylor coefficients for $latex X(t)$$ correspond -to the derivatives of $latex X(t)$$ at $latex t = 0$$ in the following way: -$latex \[ - x_j^k = \frac{1}{ k ! } X_j^{(k)} (0) -\] $$ - -$head ty$$ -The argument $icode ty$$ has prototype -$codei% - CppAD::vector<%Base%>& %ty% -%$$ -and $icode%tx%.size() == (%q%+1)*%m%$$. -Upon return, -For $latex i = 0 , \ldots , m-1$$ and $latex k = 0 , \ldots , q$$, -$latex \[ -\begin{array}{rcl} - Y_i (t) & = & f_i [ X(t) ] - \\ - Y_i (t) & = & y_i^0 + y_i^1 t^1 + \cdots + y_i^q t^q + o ( t^q ) - \\ - ty [ i * ( q + 1 ) + k ] & = & y_i^k -\end{array} -\] $$ -where $latex o( t^q ) / t^q \rightarrow 0$$ as $latex t \rightarrow 0$$. -Note that superscripts represent an index for $latex y_j^k$$ -and an exponent for $latex t^k$$. -Also note that the Taylor coefficients for $latex Y(t)$$ correspond -to the derivatives of $latex Y(t)$$ at $latex t = 0$$ in the following way: -$latex \[ - y_j^k = \frac{1}{ k ! } Y_j^{(k)} (0) -\] $$ -If $latex p > 0$$, -for $latex i = 0 , \ldots , m-1$$ and $latex k = 0 , \ldots , p-1$$, -the input of $icode ty$$ satisfies -$latex \[ - ty [ i * ( q + 1 ) + k ] = y_i^k -\]$$ -and hence the corresponding elements need not be recalculated. - -$head ok$$ -If the required results are calculated, $icode ok$$ should be true. -Otherwise, it should be false. - -$head Discussion$$ -For example, suppose that $icode%q% == 2%$$, -and you know how to compute the function $latex f(x)$$, -its first derivative $latex f^{(1)} (x)$$, -and it component wise Hessian $latex f_i^{(2)} (x)$$. -Then you can compute $icode ty$$ using the following formulas: -$latex \[ -\begin{array}{rcl} -y_i^0 & = & Y(0) - = f_i ( x^0 ) -\\ -y_i^1 & = & Y^{(1)} ( 0 ) - = f_i^{(1)} ( x^0 ) X^{(1)} ( 0 ) - = f_i^{(1)} ( x^0 ) x^1 -\\ -y_i^2 -& = & \frac{1}{2 !} Y^{(2)} (0) -\\ -& = & \frac{1}{2} X^{(1)} (0)^\R{T} f_i^{(2)} ( x^0 ) X^{(1)} ( 0 ) - + \frac{1}{2} f_i^{(1)} ( x^0 ) X^{(2)} ( 0 ) -\\ -& = & \frac{1}{2} (x^1)^\R{T} f_i^{(2)} ( x^0 ) x^1 - + f_i^{(1)} ( x^0 ) x^2 -\end{array} -\] $$ -For $latex i = 0 , \ldots , m-1$$, and $latex k = 0 , 1 , 2$$, -$latex \[ - ty [ i * (q + 1) + k ] = y_i^k -\] $$ - -$children% - example/atomic/forward.cpp -%$$ -$head Examples$$ -The file $cref atomic_forward.cpp$$ contains an example and test -that uses this routine. -It returns true if the test passes and false if it fails. - -$end ------------------------------------------------------------------------------ -*/ -/*! -Link from atomic_base to forward mode - -\param p [in] -lowerest order for this forward mode calculation. - -\param q [in] -highest order for this forward mode calculation. - -\param vx [in] -if size not zero, which components of \c x are variables - -\param vy [out] -if size not zero, which components of \c y are variables - -\param tx [in] -Taylor coefficients corresponding to \c x for this calculation. - -\param ty [out] -Taylor coefficient corresponding to \c y for this calculation - -See the forward mode in user's documentation for base_atomic -*/ -virtual bool forward( - size_t p , - size_t q , - const vector& vx , - vector& vy , - const vector& tx , - vector& ty ) -{ return false; } -/* ------------------------------------------------------------------------------ -$begin atomic_reverse$$ -$spell - sq - mul.hpp - afun - ty - px - py - Taylor - const - CppAD -$$ - -$section Atomic Reverse Mode$$ -$spell - bool -$$ - -$head Syntax$$ -$icode%ok% = %afun%.reverse(%q%, %tx%, %ty%, %px%, %py%)%$$ - -$head Purpose$$ -This function is used by $cref/reverse/Reverse/$$ -to compute derivatives. - -$head Implementation$$ -If you are using -$cref/reverse/Reverse/$$ mode, -this virtual function must be defined by the -$cref/atomic_user/atomic_ctor/atomic_user/$$ class. -It can just return $icode%ok% == false%$$ -(and not compute anything) for values -of $icode q$$ that are greater than those used by your -$cref/reverse/Reverse/$$ mode calculations. - -$head q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the highest order Taylor coefficient that -computing the derivative of. - -$head tx$$ -The argument $icode tx$$ has prototype -$codei% - const CppAD::vector<%Base%>& %tx% -%$$ -and $icode%tx%.size() == (%q%+1)*%n%$$. -For $latex j = 0 , \ldots , n-1$$ and $latex k = 0 , \ldots , q$$, -we use the Taylor coefficient notation -$latex \[ -\begin{array}{rcl} - x_j^k & = & tx [ j * ( q + 1 ) + k ] - \\ - X_j (t) & = & x_j^0 + x_j^1 t^1 + \cdots + x_j^q t^q -\end{array} -\] $$ -Note that superscripts represent an index for $latex x_j^k$$ -and an exponent for $latex t^k$$. -Also note that the Taylor coefficients for $latex X(t)$$ correspond -to the derivatives of $latex X(t)$$ at $latex t = 0$$ in the following way: -$latex \[ - x_j^k = \frac{1}{ k ! } X_j^{(k)} (0) -\] $$ - -$head ty$$ -The argument $icode ty$$ has prototype -$codei% - const CppAD::vector<%Base%>& %ty% -%$$ -and $icode%tx%.size() == (%q%+1)*%m%$$. -For $latex i = 0 , \ldots , m-1$$ and $latex k = 0 , \ldots , q$$, -we use the Taylor coefficient notation -$latex \[ -\begin{array}{rcl} - Y_i (t) & = & f_i [ X(t) ] - \\ - Y_i (t) & = & y_i^0 + y_i^1 t^1 + \cdots + y_i^q t^q + o ( t^q ) - \\ - y_i^k & = & ty [ i * ( q + 1 ) + k ] -\end{array} -\] $$ -where $latex o( t^q ) / t^q \rightarrow 0$$ as $latex t \rightarrow 0$$. -Note that superscripts represent an index for $latex y_j^k$$ -and an exponent for $latex t^k$$. -Also note that the Taylor coefficients for $latex Y(t)$$ correspond -to the derivatives of $latex Y(t)$$ at $latex t = 0$$ in the following way: -$latex \[ - y_j^k = \frac{1}{ k ! } Y_j^{(k)} (0) -\] $$ - - -$head F$$ -We use the notation $latex \{ x_j^k \} \in B^{n \times (q+1)}$$ for -$latex \[ - \{ x_j^k \W{:} j = 0 , \ldots , n-1, k = 0 , \ldots , q \} -\]$$ -We use the notation $latex \{ y_i^k \} \in B^{m \times (q+1)}$$ for -$latex \[ - \{ y_i^k \W{:} i = 0 , \ldots , m-1, k = 0 , \ldots , q \} -\]$$ -We define the function -$latex F : B^{n \times (q+1)} \rightarrow B^{m \times (q+1)}$$ by -$latex \[ - y_i^k = F_i^k [ \{ x_j^k \} ] -\] $$ -Note that -$latex \[ - F_i^0 ( \{ x_j^k \} ) = f_i ( X(0) ) = f_i ( x^0 ) -\] $$ -We also note that -$latex F_i^\ell ( \{ x_j^k \} )$$ is a function of -$latex x^0 , \ldots , x^\ell$$ -and is determined by the derivatives of $latex f_i (x)$$ -up to order $latex \ell$$. - - -$head G, H$$ -We use $latex G : B^{m \times (q+1)} \rightarrow B$$ -to denote an arbitrary scalar valued function of $latex \{ y_i^k \}$$. -We use $latex H : B^{n \times (q+1)} \rightarrow B$$ -defined by -$latex \[ - H ( \{ x_j^k \} ) = G[ F( \{ x_j^k \} ) ] -\] $$ - -$head py$$ -The argument $icode py$$ has prototype -$codei% - const CppAD::vector<%Base%>& %py% -%$$ -and $icode%py%.size() == m * (%q%+1)%$$. -For $latex i = 0 , \ldots , m-1$$, $latex k = 0 , \ldots , q$$, -$latex \[ - py[ i * (q + 1 ) + k ] = \partial G / \partial y_i^k -\] $$ - -$subhead px$$ -The $icode px$$ has prototype -$codei% - CppAD::vector<%Base%>& %px% -%$$ -and $icode%px%.size() == n * (%q%+1)%$$. -The input values of the elements of $icode px$$ -are not specified (must not matter). -Upon return, -for $latex j = 0 , \ldots , n-1$$ and $latex \ell = 0 , \ldots , q$$, -$latex \[ -\begin{array}{rcl} -px [ j * (q + 1) + \ell ] & = & \partial H / \partial x_j^\ell -\\ -& = & -( \partial G / \partial \{ y_i^k \} ) \cdot - ( \partial \{ y_i^k \} / \partial x_j^\ell ) -\\ -& = & -\sum_{k=0}^q -\sum_{i=0}^{m-1} -( \partial G / \partial y_i^k ) ( \partial y_i^k / \partial x_j^\ell ) -\\ -& = & -\sum_{k=\ell}^q -\sum_{i=0}^{m-1} -py[ i * (q + 1 ) + k ] ( \partial F_i^k / \partial x_j^\ell ) -\end{array} -\] $$ -Note that we have used the fact that for $latex k < \ell$$, -$latex \partial F_i^k / \partial x_j^\ell = 0$$. - -$head ok$$ -The return value $icode ok$$ has prototype -$codei% - bool %ok% -%$$ -If it is $code true$$, the corresponding evaluation succeeded, -otherwise it failed. - -$children% - example/atomic/reverse.cpp -%$$ -$head Examples$$ -The file $cref atomic_forward.cpp$$ contains an example and test -that uses this routine. -It returns true if the test passes and false if it fails. - -$end ------------------------------------------------------------------------------ -*/ -/*! -Link from reverse mode sweep to users routine. - -\param q [in] -highest order for this reverse mode calculation. - -\param tx [in] -Taylor coefficients corresponding to \c x for this calculation. - -\param ty [in] -Taylor coefficient corresponding to \c y for this calculation - -\param px [out] -Partials w.r.t. the \c x Taylor coefficients. - -\param py [in] -Partials w.r.t. the \c y Taylor coefficients. - -See atomic_reverse mode use documentation -*/ -virtual bool reverse( - size_t q , - const vector& tx , - const vector& ty , - vector& px , - const vector& py ) -{ return false; } -/* --------------------------------------- --------------------------------------- -$begin atomic_for_sparse_jac$$ -$spell - sq - mul.hpp - afun - Jacobian - jac - const - CppAD - std - bool - std -$$ - -$section Atomic Forward Jacobian Sparsity Patterns$$ - -$head Syntax$$ -$icode%ok% = %afun%.for_sparse_jac(%q%, %r%, %s%, %x%) -%$$ - -$head Deprecated 2016-06-27$$ -$icode%ok% = %afun%.for_sparse_jac(%q%, %r%, %s%) -%$$ - -$head Purpose$$ -This function is used by $cref ForSparseJac$$ to compute -Jacobian sparsity patterns. -For a fixed matrix $latex R \in B^{n \times q}$$, -the Jacobian of $latex f( x + R * u)$$ with respect to $latex u \in B^q$$ is -$latex \[ - S(x) = f^{(1)} (x) * R -\] $$ -Given a $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for $latex R$$, -$code for_sparse_jac$$ computes a sparsity pattern for $latex S(x)$$. - -$head Implementation$$ -If you are using -$cref ForSparseJac$$, -$cref ForSparseHes$$, or -$cref RevSparseHes$$, -one of the versions of this -virtual function must be defined by the -$cref/atomic_user/atomic_ctor/atomic_user/$$ class. - -$subhead q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of columns in -$latex R \in B^{n \times q}$$ and the Jacobian -$latex S(x) \in B^{m \times q}$$. - -$subhead r$$ -This argument has prototype -$codei% - const %atomic_sparsity%& %r% -%$$ -and is a $cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -$latex R \in B^{n \times q}$$. - -$subhead s$$ -This argument has prototype -$codei% - %atomic_sparsity%& %s% -%$$ -The input values of its elements -are not specified (must not matter). -Upon return, $icode s$$ is a -$cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -$latex S(x) \in B^{m \times q}$$. - -$subhead x$$ -$index deprecated$$ -The argument has prototype -$codei% - const CppAD::vector<%Base%>& %x% -%$$ -and size is equal to the $icode n$$. -This is the $cref Value$$ value corresponding to the parameters in the -vector $cref/ax/atomic_afun/ax/$$ (when the atomic function was called). -To be specific, if -$codei% - if( Parameter(%ax%[%i%]) == true ) - %x%[%i%] = Value( %ax%[%i%] ); - else - %x%[%i%] = CppAD::numeric_limits<%Base%>::quiet_NaN(); -%$$ -The version of this function with out the $icode x$$ argument is deprecated; -i.e., you should include the argument even if you do not use it. - -$head ok$$ -The return value $icode ok$$ has prototype -$codei% - bool %ok% -%$$ -If it is $code true$$, the corresponding evaluation succeeded, -otherwise it failed. - -$children% - example/atomic/for_sparse_jac.cpp -%$$ -$head Examples$$ -The file $cref atomic_for_sparse_jac.cpp$$ contains an example and test -that uses this routine. -It returns true if the test passes and false if it fails. - -$end ------------------------------------------------------------------------------ -*/ -/*! -Link from forward Jacobian sparsity sweep to atomic_base - -\param q -is the column dimension for the Jacobian sparsity partterns. - -\param r -is the Jacobian sparsity pattern for the argument vector x - -\param s -is the Jacobian sparsity pattern for the result vector y - -\param x -is the integer value for x arguments that are parameters. -*/ -virtual bool for_sparse_jac( - size_t q , - const vector< std::set >& r , - vector< std::set >& s , - const vector& x ) -{ return false; } -virtual bool for_sparse_jac( - size_t q , - const vector& r , - vector& s , - const vector& x ) -{ return false; } -virtual bool for_sparse_jac( - size_t q , - const vectorBool& r , - vectorBool& s , - const vector& x ) -{ return false; } -// deprecated versions -virtual bool for_sparse_jac( - size_t q , - const vector< std::set >& r , - vector< std::set >& s ) -{ return false; } -virtual bool for_sparse_jac( - size_t q , - const vector& r , - vector& s ) -{ return false; } -virtual bool for_sparse_jac( - size_t q , - const vectorBool& r , - vectorBool& s ) -{ return false; } -/* --------------------------------------- --------------------------------------- -$begin atomic_rev_sparse_jac$$ -$spell - sq - mul.hpp - rt - afun - Jacobian - jac - CppAD - std - bool - const - hes -$$ - -$section Atomic Reverse Jacobian Sparsity Patterns$$ - -$head Syntax$$ -$icode%ok% = %afun%.rev_sparse_jac(%q%, %rt%, %st%, %x%) -%$$ - -$head Deprecated 2016-06-27$$ -$icode%ok% = %afun%.rev_sparse_jac(%q%, %rt%, %st%) -%$$ - -$head Purpose$$ -This function is used by -$cref RevSparseJac$$ to compute -Jacobian sparsity patterns. -If you are using $cref RevSparseJac$$, -one of the versions of this -virtual function must be defined by the -$cref/atomic_user/atomic_ctor/atomic_user/$$ class. -$pre - -$$ -For a fixed matrix $latex R \in B^{q \times m}$$, -the Jacobian of $latex R * f( x )$$ with respect to $latex x \in B^n$$ is -$latex \[ - S(x) = R * f^{(1)} (x) -\] $$ -Given a $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for $latex R$$, -$code rev_sparse_jac$$ computes a sparsity pattern for $latex S(x)$$. - -$head Implementation$$ -If you are using -$cref RevSparseJac$$ or $cref ForSparseHes$$, -this virtual function must be defined by the -$cref/atomic_user/atomic_ctor/atomic_user/$$ class. - -$subhead q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of rows in -$latex R \in B^{q \times m}$$ and the Jacobian -$latex S(x) \in B^{q \times n}$$. - -$subhead rt$$ -This argument has prototype -$codei% - const %atomic_sparsity%& %rt% -%$$ -and is a -$cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -$latex R^\R{T} \in B^{m \times q}$$. - -$subhead st$$ -This argument has prototype -$codei% - %atomic_sparsity%& %st% -%$$ -The input value of its elements -are not specified (must not matter). -Upon return, $icode s$$ is a -$cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -$latex S(x)^\R{T} \in B^{n \times q}$$. - -$subhead x$$ -$index deprecated$$ -The argument has prototype -$codei% - const CppAD::vector<%Base%>& %x% -%$$ -and size is equal to the $icode n$$. -This is the $cref Value$$ corresponding to the parameters in the -vector $cref/ax/atomic_afun/ax/$$ (when the atomic function was called). -To be specific, if -$codei% - if( Parameter(%ax%[%i%]) == true ) - %x%[%i%] = Value( %ax%[%i%] ); - else - %x%[%i%] = CppAD::numeric_limits<%Base%>::quiet_NaN(); -%$$ -The version of this function with out the $icode x$$ argument is deprecated; -i.e., you should include the argument even if you do not use it. - -$head ok$$ -The return value $icode ok$$ has prototype -$codei% - bool %ok% -%$$ -If it is $code true$$, the corresponding evaluation succeeded, -otherwise it failed. - -$children% - example/atomic/rev_sparse_jac.cpp -%$$ -$head Examples$$ -The file $cref atomic_rev_sparse_jac.cpp$$ contains an example and test -that uses this routine. -It returns true if the test passes and false if it fails. - -$end ------------------------------------------------------------------------------ -*/ -/*! -Link from reverse Jacobian sparsity sweep to atomic_base - -\param q [in] -is the row dimension for the Jacobian sparsity partterns - -\param rt [out] -is the tansposed Jacobian sparsity pattern w.r.t to range variables y - -\param st [in] -is the tansposed Jacobian sparsity pattern for the argument variables x - -\param x -is the integer value for x arguments that are parameters. -*/ -virtual bool rev_sparse_jac( - size_t q , - const vector< std::set >& rt , - vector< std::set >& st , - const vector& x ) -{ return false; } -virtual bool rev_sparse_jac( - size_t q , - const vector& rt , - vector& st , - const vector& x ) -{ return false; } -virtual bool rev_sparse_jac( - size_t q , - const vectorBool& rt , - vectorBool& st , - const vector& x ) -{ return false; } -// deprecated versions -virtual bool rev_sparse_jac( - size_t q , - const vector< std::set >& rt , - vector< std::set >& st ) -{ return false; } -virtual bool rev_sparse_jac( - size_t q , - const vector& rt , - vector& st ) -{ return false; } -virtual bool rev_sparse_jac( - size_t q , - const vectorBool& rt , - vectorBool& st ) -{ return false; } -/* --------------------------------------- --------------------------------------- -$begin atomic_for_sparse_hes$$ -$spell - sq - mul.hpp - vx - afun - Jacobian - jac - CppAD - std - bool - hes - const -$$ - -$section Atomic Forward Hessian Sparsity Patterns$$ - -$head Syntax$$ -$icode%ok% = %afun%.for_sparse_hes(%vx%, %r%, %s%, %h%, %x%)%$$ - -$head Deprecated 2016-06-27$$ -$icode%ok% = %afun%.for_sparse_hes(%vx%, %r%, %s%, %h%)%$$ - -$head Purpose$$ -This function is used by $cref ForSparseHes$$ to compute -Hessian sparsity patterns. -If you are using $cref ForSparseHes$$, -one of the versions of this -virtual function must be defined by the -$cref/atomic_user/atomic_ctor/atomic_user/$$ class. -$pre - -$$ -Given a $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for -a diagonal matrix $latex R \in B^{n \times n}$$, and -a row vector $latex S \in B^{1 \times m}$$, -this routine computes the sparsity pattern for -$latex \[ - H(x) = R^\R{T} \cdot (S \cdot f)^{(2)}( x ) \cdot R -\] $$ - -$head Implementation$$ -If you are using and $cref ForSparseHes$$, -this virtual function must be defined by the -$cref/atomic_user/atomic_ctor/atomic_user/$$ class. - -$subhead vx$$ -The argument $icode vx$$ has prototype -$codei% - const CppAD:vector& %vx% -%$$ -$icode%vx%.size() == %n%$$, and -for $latex j = 0 , \ldots , n-1$$, -$icode%vx%[%j%]%$$ is true if and only if -$icode%ax%[%j%]%$$ is a $cref/variable/glossary/Variable/$$ -in the corresponding call to -$codei% - %afun%(%ax%, %ay%) -%$$ - -$subhead r$$ -This argument has prototype -$codei% - const CppAD:vector& %r% -%$$ -and is a $cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -the diagonal of $latex R \in B^{n \times n}$$. - -$subhead s$$ -The argument $icode s$$ has prototype -$codei% - const CppAD:vector& %s% -%$$ -and its size is $icode m$$. -It is a sparsity pattern for $latex S \in B^{1 \times m}$$. - -$subhead h$$ -This argument has prototype -$codei% - %atomic_sparsity%& %h% -%$$ -The input value of its elements -are not specified (must not matter). -Upon return, $icode h$$ is a -$cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -$latex H(x) \in B^{n \times n}$$ which is defined above. - -$subhead x$$ -$index deprecated$$ -The argument has prototype -$codei% - const CppAD::vector<%Base%>& %x% -%$$ -and size is equal to the $icode n$$. -This is the $cref Value$$ value corresponding to the parameters in the -vector $cref/ax/atomic_afun/ax/$$ (when the atomic function was called). -To be specific, if -$codei% - if( Parameter(%ax%[%i%]) == true ) - %x%[%i%] = Value( %ax%[%i%] ); - else - %x%[%i%] = CppAD::numeric_limits<%Base%>::quiet_NaN(); -%$$ -The version of this function with out the $icode x$$ argument is deprecated; -i.e., you should include the argument even if you do not use it. - -$children% - example/atomic/for_sparse_hes.cpp -%$$ -$head Examples$$ -The file $cref atomic_for_sparse_hes.cpp$$ contains an example and test -that uses this routine. -It returns true if the test passes and false if it fails. - -$end ------------------------------------------------------------------------------ -*/ -/*! -Link from forward Hessian sparsity sweep to base_atomic - -\param vx [in] -which componens of x are variables. - -\param r [in] -is the forward Jacobian sparsity pattern w.r.t the argument vector x. - -\param s [in] -is the reverse Jacobian sparsity pattern w.r.t the result vector y. - -\param h [out] -is the Hessian sparsity pattern w.r.t the argument vector x. - -\param x -is the integer value of the x arguments that are parameters. -*/ -virtual bool for_sparse_hes( - const vector& vx , - const vector& r , - const vector& s , - vector< std::set >& h , - const vector& x ) -{ return false; } -virtual bool for_sparse_hes( - const vector& vx , - const vector& r , - const vector& s , - vector& h , - const vector& x ) -{ return false; } -virtual bool for_sparse_hes( - const vector& vx , - const vector& r , - const vector& s , - vectorBool& h , - const vector& x ) -// deprecated -{ return false; } -virtual bool for_sparse_hes( - const vector& vx , - const vector& r , - const vector& s , - vector< std::set >& h ) -{ return false; } -// deprecated versions -virtual bool for_sparse_hes( - const vector& vx , - const vector& r , - const vector& s , - vector& h ) -{ return false; } -virtual bool for_sparse_hes( - const vector& vx , - const vector& r , - const vector& s , - vectorBool& h ) -{ return false; } -/* --------------------------------------- --------------------------------------- -$begin atomic_rev_sparse_hes$$ -$spell - sq - mul.hpp - vx - afun - Jacobian - jac - CppAD - std - bool - hes - const -$$ - -$section Atomic Reverse Hessian Sparsity Patterns$$ - -$head Syntax$$ -$icode%ok% = %afun%.rev_sparse_hes(%vx%, %s%, %t%, %q%, %r%, %u%, %v%, %x%)%$$ - -$head Deprecated 2016-06-27$$ -$icode%ok% = %afun%.rev_sparse_hes(%vx%, %s%, %t%, %q%, %r%, %u%, %v%)%$$ - -$head Purpose$$ -This function is used by $cref RevSparseHes$$ to compute -Hessian sparsity patterns. -If you are using $cref RevSparseHes$$ to compute -one of the versions of this -virtual function muse be defined by the -$cref/atomic_user/atomic_ctor/atomic_user/$$ class. -$pre - -$$ -There is an unspecified scalar valued function -$latex g : B^m \rightarrow B$$. -Given a $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for -$latex R \in B^{n \times q}$$, -and information about the function $latex z = g(y)$$, -this routine computes the sparsity pattern for -$latex \[ - V(x) = (g \circ f)^{(2)}( x ) R -\] $$ - -$head Implementation$$ -If you are using and $cref RevSparseHes$$, -this virtual function must be defined by the -$cref/atomic_user/atomic_ctor/atomic_user/$$ class. - -$subhead vx$$ -The argument $icode vx$$ has prototype -$codei% - const CppAD:vector& %vx% -%$$ -$icode%vx%.size() == %n%$$, and -for $latex j = 0 , \ldots , n-1$$, -$icode%vx%[%j%]%$$ is true if and only if -$icode%ax%[%j%]%$$ is a $cref/variable/glossary/Variable/$$ -in the corresponding call to -$codei% - %afun%(%ax%, %ay%) -%$$ - -$subhead s$$ -The argument $icode s$$ has prototype -$codei% - const CppAD:vector& %s% -%$$ -and its size is $icode m$$. -It is a sparsity pattern for -$latex S(x) = g^{(1)} [ f(x) ] \in B^{1 \times m}$$. - -$subhead t$$ -This argument has prototype -$codei% - CppAD:vector& %t% -%$$ -and its size is $icode m$$. -The input values of its elements -are not specified (must not matter). -Upon return, $icode t$$ is a -sparsity pattern for -$latex T(x) \in B^{1 \times n}$$ where -$latex \[ - T(x) = (g \circ f)^{(1)} (x) = S(x) * f^{(1)} (x) -\]$$ - -$subhead q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of columns in -$latex R \in B^{n \times q}$$, -$latex U(x) \in B^{m \times q}$$, and -$latex V(x) \in B^{n \times q}$$. - -$subhead r$$ -This argument has prototype -$codei% - const %atomic_sparsity%& %r% -%$$ -and is a $cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -$latex R \in B^{n \times q}$$. - -$head u$$ -This argument has prototype -$codei% - const %atomic_sparsity%& %u% -%$$ -and is a $cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -$latex U(x) \in B^{m \times q}$$ which is defined by -$latex \[ -\begin{array}{rcl} -U(x) -& = & -\{ \partial_u \{ \partial_y g[ y + f^{(1)} (x) R u ] \}_{y=f(x)} \}_{u=0} -\\ -& = & -\partial_u \{ g^{(1)} [ f(x) + f^{(1)} (x) R u ] \}_{u=0} -\\ -& = & -g^{(2)} [ f(x) ] f^{(1)} (x) R -\end{array} -\] $$ - -$subhead v$$ -This argument has prototype -$codei% - %atomic_sparsity%& %v% -%$$ -The input value of its elements -are not specified (must not matter). -Upon return, $icode v$$ is a -$cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -$latex V(x) \in B^{n \times q}$$ which is defined by -$latex \[ -\begin{array}{rcl} -V(x) -& = & -\partial_u [ \partial_x (g \circ f) ( x + R u ) ]_{u=0} -\\ -& = & -\partial_u [ (g \circ f)^{(1)}( x + R u ) ]_{u=0} -\\ -& = & -(g \circ f)^{(2)}( x ) R -\\ -& = & -f^{(1)} (x)^\R{T} g^{(2)} [ f(x) ] f^{(1)} (x) R -+ -\sum_{i=1}^m g_i^{(1)} [ f(x) ] \; f_i^{(2)} (x) R -\\ -& = & -f^{(1)} (x)^\R{T} U(x) -+ -\sum_{i=1}^m S_i (x) \; f_i^{(2)} (x) R -\end{array} -\] $$ - -$subhead x$$ -$index deprecated$$ -The argument has prototype -$codei% - const CppAD::vector<%Base%>& %x% -%$$ -and size is equal to the $icode n$$. -This is the $cref Value$$ value corresponding to the parameters in the -vector $cref/ax/atomic_afun/ax/$$ (when the atomic function was called). -To be specific, if -$codei% - if( Parameter(%ax%[%i%]) == true ) - %x%[%i%] = Value( %ax%[%i%] ); - else - %x%[%i%] = CppAD::numeric_limits<%Base%>::quiet_NaN(); -%$$ -The version of this function with out the $icode x$$ argument is deprecated; -i.e., you should include the argument even if you do not use it. - -$children% - example/atomic/rev_sparse_hes.cpp -%$$ -$head Examples$$ -The file $cref atomic_rev_sparse_hes.cpp$$ contains an example and test -that uses this routine. -It returns true if the test passes and false if it fails. - -$end ------------------------------------------------------------------------------ -*/ -/*! -Link from reverse Hessian sparsity sweep to base_atomic - -\param vx [in] -which componens of x are variables. - -\param s [in] -is the reverse Jacobian sparsity pattern w.r.t the result vector y. - -\param t [out] -is the reverse Jacobian sparsity pattern w.r.t the argument vector x. - -\param q [in] -is the column dimension for the sparsity partterns. - -\param r [in] -is the forward Jacobian sparsity pattern w.r.t the argument vector x - -\param u [in] -is the Hessian sparsity pattern w.r.t the result vector y. - -\param v [out] -is the Hessian sparsity pattern w.r.t the argument vector x. - -\param x [in] -is the integer value of the x arguments that are parameters. -*/ -virtual bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const vector< std::set >& r , - const vector< std::set >& u , - vector< std::set >& v , - const vector& x ) -{ return false; } -virtual bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const vector& r , - const vector& u , - vector& v , - const vector& x ) -{ return false; } -virtual bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const vectorBool& r , - const vectorBool& u , - vectorBool& v , - const vector& x ) -{ return false; } -// deprecated -virtual bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const vector< std::set >& r , - const vector< std::set >& u , - vector< std::set >& v ) -{ return false; } -virtual bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const vector& r , - const vector& u , - vector& v ) -{ return false; } -virtual bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const vectorBool& r , - const vectorBool& u , - vectorBool& v ) -{ return false; } -/* ------------------------------------------------------------------------------- -$begin atomic_base_clear$$ -$spell - sq - alloc -$$ - -$section Free Static Variables$$ -$mindex clear$$ - -$head Syntax$$ -$codei%atomic_base<%Base%>::clear()%$$ - -$head Purpose$$ -Each $code atomic_base$$ objects holds onto work space in order to -avoid repeated memory allocation calls and thereby increase speed -(until it is deleted). -If an the $code atomic_base$$ object is global or static because, -the it does not get deleted. -This is a problem when using -$code thread_alloc$$ $cref/free_all/ta_free_all/$$ -to check that all allocated memory has been freed. -Calling this $code clear$$ function will free all the -memory currently being held onto by the -$codei%atomic_base<%Base%>%$$ class. - -$head Future Use$$ -If there is future use of an $code atomic_base$$ object, -after a call to $code clear$$, -the work space will be reallocated and held onto. - -$head Restriction$$ -This routine cannot be called -while in $cref/parallel/ta_in_parallel/$$ execution mode. - -$end ------------------------------------------------------------------------------- -*/ -/*! -Free all thread_alloc static memory held by atomic_base (avoids reallocations). -(This does not include class_object() which is an std::vector.) -*/ -/// Free vector memory used by this class (work space) -static void clear(void) -{ CPPAD_ASSERT_KNOWN( - ! thread_alloc::in_parallel() , - "cannot use atomic_base clear during parallel execution" - ); - size_t i = class_object().size(); - while(i--) - { size_t thread = CPPAD_MAX_NUM_THREADS; - while(thread--) - { - atomic_base* op = class_object()[i]; - if( op != CPPAD_NULL ) - { op->afun_vx_[thread].clear(); - op->afun_vy_[thread].clear(); - op->afun_tx_[thread].clear(); - op->afun_ty_[thread].clear(); - } - } - } - return; -} -// ------------------------------------------------------------------------- -/*! -Set value of id (used by deprecated old_atomic class) - -This function is called just before calling any of the virtual function -and has the corresponding id of the corresponding virtual call. -*/ -virtual void set_old(size_t id) -{ } -// --------------------------------------------------------------------------- -}; -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/azmul.hpp b/ct_core/include/ct/external/cppad/core/azmul.hpp deleted file mode 100644 index f6dfe7741..000000000 --- a/ct_core/include/ct/external/cppad/core/azmul.hpp +++ /dev/null @@ -1,214 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_AZMUL_HPP -# define CPPAD_CORE_AZMUL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin azmul$$ -$spell - azmul - const - namespace - Vec -$$ - -$section Absolute Zero Multiplication$$ - -$head Syntax$$ -$icode%z% = azmul(%x%, %y%)%$$ - -$head Purpose$$ -Evaluates multiplication with an absolute zero -for any of the possible types listed below. -The result is given by -$latex \[ -z = \left\{ \begin{array}{ll} - 0 & {\rm if} \; x = 0 \\ - x \cdot y & {\rm otherwise} -\end{array} \right. -\] $$ -Note if $icode x$$ is zero and $icode y$$ is infinity, -ieee multiplication would result in not a number whereas -$icode z$$ would be zero. - -$head Base$$ -If $icode Base$$ satisfies the -$cref/base type requirements/base_require/$$ -and arguments $icode x$$, $icode y$$ have prototypes -$codei% - const %Base%& %x% - const %Base%& %y% -%$$ -then the result $icode z$$ has prototype -$codei% - %Base% %z% -%$$ - -$head AD$$ -If the arguments $icode x$$, $icode y$$ have prototype -$codei% - const AD<%Base%>& %x% - const AD<%Base%>& %y% -%$$ -then the result $icode z$$ has prototype -$codei% - AD<%Base%> %z% -%$$ - -$head VecAD$$ -If the arguments $icode x$$, $icode y$$ have prototype -$codei% - const VecAD<%Base%>::reference& %x% - const VecAD<%Base%>::reference& %y% -%$$ -then the result $icode z$$ has prototype -$codei% - AD<%Base%> %z% -%$$ - -$head Example$$ -$children% - example/azmul.cpp -%$$ -The file -$cref azmul.cpp$$ -is an examples and tests of this function. -It returns true if it succeeds and false otherwise. - -$end -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -// ========================================================================== - -// case where x and y are AD ------------------------------------------- -template AD -azmul(const AD& x, const AD& y) -{ - // compute the Base part - AD result; - result.value_ = azmul(x.value_, y.value_); - - // check if there is a recording in progress - local::ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return result; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_x = x.tape_id_ == tape_id; - bool var_y = y.tape_id_ == tape_id; - - if( var_x ) - { if( var_y ) - { // result = azmul(variable, variable) - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::ZmulvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::ZmulvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(x.taddr_, y.taddr_); - - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::ZmulvvOp); - - // make result a variable - result.tape_id_ = tape_id; - } - else if( IdenticalZero( y.value_ ) ) - { // result = variable * 0 - } - else if( IdenticalOne( y.value_ ) ) - { // result = variable * 1 - result.make_variable(x.tape_id_, x.taddr_); - } - else - { // result = zmul(variable, parameter) - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::ZmulvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::ZmulvpOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(y.value_); - tape->Rec_.PutArg(x.taddr_, p); - - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::ZmulvpOp); - - // make result a variable - result.tape_id_ = tape_id; - } - } - else if( var_y ) - { if( IdenticalZero(x.value_) ) - { // result = 0 * variable - } - else if( IdenticalOne( x.value_ ) ) - { // result = 1 * variable - result.make_variable(y.tape_id_, y.taddr_); - } - else - { // result = zmul(parameter, variable) - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::ZmulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::ZmulpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(x.value_); - tape->Rec_.PutArg(p, y.taddr_); - - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::ZmulpvOp); - - // make result a variable - result.tape_id_ = tape_id; - } - } - return result; -} -// ========================================================================= -// Fold operations into case above -// ------------------------------------------------------------------------- -// Operations with VecAD_reference and AD only - -template AD -azmul(const AD& x, const VecAD_reference& y) -{ return azmul(x, y.ADBase()); } - -template AD -azmul(const VecAD_reference& x, const VecAD_reference& y) -{ return azmul(x.ADBase(), y.ADBase()); } - -template AD -azmul(const VecAD_reference& x, const AD& y) -{ return azmul(x.ADBase(), y); } -// ------------------------------------------------------------------------- -// Operations with Base - -template AD -azmul(const Base& x, const AD& y) -{ return azmul(AD(x), y); } - -template AD -azmul(const Base& x, const VecAD_reference& y) -{ return azmul(AD(x), y.ADBase()); } - -template AD -azmul(const AD& x, const Base& y) -{ return azmul(x, AD(y)); } - -template AD -azmul(const VecAD_reference& x, const Base& y) -{ return azmul(x.ADBase(), AD(y)); } - -// ========================================================================== -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/core/base_complex.hpp b/ct_core/include/ct/external/cppad/core/base_complex.hpp deleted file mode 100644 index 9b8868dcb..000000000 --- a/ct_core/include/ct/external/cppad/core/base_complex.hpp +++ /dev/null @@ -1,384 +0,0 @@ -# ifndef CPPAD_CORE_BASE_COMPLEX_HPP -# define CPPAD_CORE_BASE_COMPLEX_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-17 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include -# include - -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -/* -$begin base_complex.hpp$$ -$spell - azmul - expm1 - atanh - acosh - asinh - endif - eps - abs_geq - Rel - Lt Le Eq Ge Gt - imag - gcc - isnan - cppad.hpp - sqrt - exp - cos - std - const - CppAD - Op - inline - enum - undef - acos - asin - atan - erf - Cond - namespace - bool -$$ - - -$section Enable use of AD where Base is std::complex$$ - -$children%example/complex_poly.cpp -%$$ -$head Example$$ -The file $cref complex_poly.cpp$$ contains an example use of -$code std::complex$$ type for a CppAD $icode Base$$ type. -It returns true if it succeeds and false otherwise. - -$head Include Order$$ -This file is included before $code $$ -so it is necessary to define the error handler -in addition to including -$cref/base_require.hpp/base_require/Include Order/$$ -$srccode%cpp% */ -# include -# include -# include -# include - -/* %$$ - -$head CondExpOp$$ -The type $code std::complex$$ does not supports the -$code <$$, $code <=$$, $code ==$$, $code >=$$, and $code >$$ operators; see -$cref/not ordered/base_cond_exp/CondExpTemplate/Not Ordered/$$. -Hence its $code CondExpOp$$ function is defined by -$srccode%cpp% */ -namespace CppAD { - inline std::complex CondExpOp( - enum CppAD::CompareOp cop , - const std::complex &left , - const std::complex &right , - const std::complex &trueCase , - const std::complex &falseCase ) - { CppAD::ErrorHandler::Call( - true , __LINE__ , __FILE__ , - "std::complex CondExpOp(...)", - "Error: cannot use CondExp with a complex type" - ); - return std::complex(0); - } -} -/* %$$ - -$head CondExpRel$$ -The $cref/CPPAD_COND_EXP_REL/base_cond_exp/CondExpRel/$$ macro invocation -$srccode%cpp% */ -namespace CppAD { - CPPAD_COND_EXP_REL( std::complex ) -} -/* %$$ -used $code CondExpOp$$ above to -define $codei%CondExp%Rel%$$ for $code std::complex$$ arguments -and $icode%Rel%$$ equal to -$code Lt$$, $code Le$$, $code Eq$$, $code Ge$$, and $code Gt$$. - -$head EqualOpSeq$$ -Complex numbers do not carry operation sequence information. -Thus they are equal in this sense if and only if there values are equal. -$srccode%cpp% */ -namespace CppAD { - inline bool EqualOpSeq( - const std::complex &x , - const std::complex &y ) - { return x == y; - } -} -/* %$$ - -$head Identical$$ -Complex numbers do not carry operation sequence information. -Thus they are all parameters so the identical functions just check values. -$srccode%cpp% */ -namespace CppAD { - inline bool IdenticalPar(const std::complex &x) - { return true; } - inline bool IdenticalZero(const std::complex &x) - { return (x == std::complex(0., 0.) ); } - inline bool IdenticalOne(const std::complex &x) - { return (x == std::complex(1., 0.) ); } - inline bool IdenticalEqualPar( - const std::complex &x, const std::complex &y) - { return (x == y); } -} -/* %$$ - -$head Ordered$$ -Complex types do not support comparison operators, -$srccode%cpp% */ -# undef CPPAD_USER_MACRO -# define CPPAD_USER_MACRO(Fun) \ -inline bool Fun(const std::complex& x) \ -{ CppAD::ErrorHandler::Call( \ - true , __LINE__ , __FILE__ , \ - #Fun"(x)", \ - "Error: cannot use " #Fun " with x complex " \ - ); \ - return false; \ -} -namespace CppAD { - CPPAD_USER_MACRO(LessThanZero) - CPPAD_USER_MACRO(LessThanOrZero) - CPPAD_USER_MACRO(GreaterThanOrZero) - CPPAD_USER_MACRO(GreaterThanZero) - inline bool abs_geq( - const std::complex& x , - const std::complex& y ) - { return std::abs(x) >= std::abs(y); } -} -/* %$$ - -$head Integer$$ -The implementation of this function must agree -with the CppAD user specifications for complex arguments to the -$cref/Integer/Integer/x/Complex Types/$$ function: -$srccode%cpp% */ -namespace CppAD { - inline int Integer(const std::complex &x) - { return static_cast( x.real() ); } -} -/* %$$ - -$head azmul$$ -$srccode%cpp% */ -namespace CppAD { - CPPAD_AZMUL( std::complex ) -} -/* %$$ - -$head isnan$$ -The gcc 4.1.1 complier defines the function -$codei% - int std::complex::isnan( std::complex %z% ) -%$$ -(which is not specified in the C++ 1998 standard ISO/IEC 14882). -This causes an ambiguity between the function above and the CppAD -$cref/isnan/nan/$$ template function. -We avoid this ambiguity by defining a non-template version of -this function in the CppAD namespace. -$srccode%cpp% */ -namespace CppAD { - inline bool isnan(const std::complex& z) - { return (z != z); - } -} -/* %$$ - -$head Valid Unary Math$$ -The following macro invocations define the standard unary -math functions that are valid with complex arguments and are -required to use $code AD< std::complex >$$. -$srccode%cpp% */ -namespace CppAD { - CPPAD_STANDARD_MATH_UNARY(std::complex, cos) - CPPAD_STANDARD_MATH_UNARY(std::complex, cosh) - CPPAD_STANDARD_MATH_UNARY(std::complex, exp) - CPPAD_STANDARD_MATH_UNARY(std::complex, log) - CPPAD_STANDARD_MATH_UNARY(std::complex, sin) - CPPAD_STANDARD_MATH_UNARY(std::complex, sinh) - CPPAD_STANDARD_MATH_UNARY(std::complex, sqrt) -} -/* %$$ - -$head Invalid Unary Math$$ -The following macro definition and invocations define the standard unary -math functions that are invalid with complex arguments and are -required to use $code AD< std::complex >$$. -$srccode%cpp% */ -# undef CPPAD_USER_MACRO -# define CPPAD_USER_MACRO(Fun) \ -inline std::complex Fun(const std::complex& x) \ -{ CppAD::ErrorHandler::Call( \ - true , __LINE__ , __FILE__ , \ - #Fun"(x)", \ - "Error: cannot use " #Fun " with x complex " \ - ); \ - return std::complex(0); \ -} -namespace CppAD { - CPPAD_USER_MACRO(abs) - CPPAD_USER_MACRO(fabs) - CPPAD_USER_MACRO(acos) - CPPAD_USER_MACRO(asin) - CPPAD_USER_MACRO(atan) - CPPAD_USER_MACRO(sign) -# if CPPAD_USE_CPLUSPLUS_2011 - CPPAD_USER_MACRO(erf) - CPPAD_USER_MACRO(asinh) - CPPAD_USER_MACRO(acosh) - CPPAD_USER_MACRO(atanh) - CPPAD_USER_MACRO(expm1) - CPPAD_USER_MACRO(log1p) -# endif -} -/* %$$ - -$head pow $$ -The following defines a $code CppAD::pow$$ function that -is required to use $code AD< std::complex >$$: -$srccode%cpp% */ -namespace CppAD { - inline std::complex pow( - const std::complex &x , - const std::complex &y ) - { return std::pow(x, y); } -} -/* %$$ - -$head numeric_limits$$ -The following defines the CppAD $cref numeric_limits$$ -for the type $code std::complex$$: -$srccode%cpp% */ -namespace CppAD { - CPPAD_NUMERIC_LIMITS(double, std::complex) -} -/* %$$ - -$head to_string$$ -The following defines the function CppAD $cref to_string$$ -for the type $code std::complex$$: -$srccode%cpp% */ -namespace CppAD { - CPPAD_TO_STRING(std::complex) -} -/* %$$ -$end -*/ -# undef CPPAD_USER_MACRO_ONE -# define CPPAD_USER_MACRO_ONE(Fun) \ -inline bool Fun(const std::complex& x) \ -{ CppAD::ErrorHandler::Call( \ - true , __LINE__ , __FILE__ , \ - #Fun"(x)", \ - "Error: cannot use " #Fun " with x complex " \ - ); \ - return false; \ -} -# undef CPPAD_USER_MACRO_TWO -# define CPPAD_USER_MACRO_TWO(Fun) \ -inline std::complex Fun(const std::complex& x) \ -{ CppAD::ErrorHandler::Call( \ - true , __LINE__ , __FILE__ , \ - #Fun"(x)", \ - "Error: cannot use " #Fun " with x complex " \ - ); \ - return std::complex(0); \ -} -namespace CppAD { - // CondExpOp ------------------------------------------------------ - inline std::complex CondExpOp( - enum CppAD::CompareOp cop , - const std::complex &left , - const std::complex &right , - const std::complex &trueCase , - const std::complex &falseCase ) - { CppAD::ErrorHandler::Call( - true , __LINE__ , __FILE__ , - "std::complex CondExpOp(...)", - "Error: cannot use CondExp with a complex type" - ); - return std::complex(0); - } - // CondExpRel -------------------------------------------------------- - CPPAD_COND_EXP_REL( std::complex ) - // EqualOpSeq ----------------------------------------------------- - inline bool EqualOpSeq( - const std::complex &x , - const std::complex &y ) - { return x == y; - } - // Identical ------------------------------------------------------ - inline bool IdenticalPar(const std::complex &x) - { return true; } - inline bool IdenticalZero(const std::complex &x) - { return (x == std::complex(0., 0.) ); } - inline bool IdenticalOne(const std::complex &x) - { return (x == std::complex(1., 0.) ); } - inline bool IdenticalEqualPar( - const std::complex &x, const std::complex &y) - { return (x == y); } - // Ordered -------------------------------------------------------- - CPPAD_USER_MACRO_ONE(LessThanZero) - CPPAD_USER_MACRO_ONE(LessThanOrZero) - CPPAD_USER_MACRO_ONE(GreaterThanOrZero) - CPPAD_USER_MACRO_ONE(GreaterThanZero) - inline bool abs_geq( - const std::complex& x , - const std::complex& y ) - { return std::abs(x) >= std::abs(y); } - // Integer ------------------------------------------------------ - inline int Integer(const std::complex &x) - { return static_cast( x.real() ); } - // isnan ------------------------------------------------------------- - inline bool isnan(const std::complex& z) - { return (z != z); - } - // Valid standard math functions -------------------------------- - CPPAD_STANDARD_MATH_UNARY(std::complex, cos) - CPPAD_STANDARD_MATH_UNARY(std::complex, cosh) - CPPAD_STANDARD_MATH_UNARY(std::complex, exp) - CPPAD_STANDARD_MATH_UNARY(std::complex, log) - CPPAD_STANDARD_MATH_UNARY(std::complex, sin) - CPPAD_STANDARD_MATH_UNARY(std::complex, sinh) - CPPAD_STANDARD_MATH_UNARY(std::complex, sqrt) - // Invalid standrd math functions ------------------------------- - CPPAD_USER_MACRO_TWO(abs) - CPPAD_USER_MACRO_TWO(acos) - CPPAD_USER_MACRO_TWO(asin) - CPPAD_USER_MACRO_TWO(atan) - CPPAD_USER_MACRO_TWO(sign) - // The pow function - inline std::complex pow( - const std::complex &x , - const std::complex &y ) - { return std::pow(x, y); } - // numeric_limits ------------------------------------------------- - CPPAD_NUMERIC_LIMITS(float, std::complex) - // to_string ------------------------------------------------- - CPPAD_TO_STRING(std::complex) -} - -// undefine macros only used by this file -# undef CPPAD_USER_MACRO -# undef CPPAD_USER_MACRO_ONE -# undef CPPAD_USER_MACRO_TWO - -# endif diff --git a/ct_core/include/ct/external/cppad/core/base_cond_exp.hpp b/ct_core/include/ct/external/cppad/core/base_cond_exp.hpp deleted file mode 100644 index c77c0c29b..000000000 --- a/ct_core/include/ct/external/cppad/core/base_cond_exp.hpp +++ /dev/null @@ -1,281 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_BASE_COND_EXP_HPP -# define CPPAD_CORE_BASE_COND_EXP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin base_cond_exp$$ -$spell - alloc - Rel - hpp - enum - namespace - Op - Lt - Le - Eq - Ge - Gt - Ne - cond - exp - const - adolc - CppAD - inline -$$ - -$section Base Type Requirements for Conditional Expressions$$ -$mindex CondExp require CPPAD_COND_EXP_REL$$ - -$head Purpose$$ -These definitions are required by the user's code to support the -$codei%AD<%Base%>%$$ type for $cref CondExp$$ operations: - -$head CompareOp$$ -The following $code enum$$ type is used in the specifications below: -$codep -namespace CppAD { - // The conditional expression operator enum type - enum CompareOp - { CompareLt, // less than - CompareLe, // less than or equal - CompareEq, // equal - CompareGe, // greater than or equal - CompareGt, // greater than - CompareNe // not equal - }; -} -$$ - -$head CondExpTemplate$$ -The type $icode Base$$ must support the syntax -$codei% - %result% = CppAD::CondExpOp( - %cop%, %left%, %right%, %exp_if_true%, %exp_if_false% - ) -%$$ -which computes implements the corresponding $cref CondExp$$ -function when the result has prototype -$codei% - %Base% %result% -%$$ -The argument $icode cop$$ has prototype -$codei% - enum CppAD::CompareOp %cop% -%$$ -The other arguments have the prototype -$codei% - const %Base%& %left% - const %Base%& %right% - const %Base%& %exp_if_true% - const %Base%& %exp_if_false% -%$$ - -$subhead Ordered Type$$ -If $icode Base$$ is a relatively simple type -that supports -$code <$$, $code <=$$, $code ==$$, $code >=$$, and $code >$$ operators -its $code CondExpOp$$ function can be defined by -$codei% -namespace CppAD { - inline %Base% CondExpOp( - enum CppAD::CompareOp cop , - const %Base% &left , - const %Base% &right , - const %Base% &exp_if_true , - const %Base% &exp_if_false ) - { return CondExpTemplate( - cop, left, right, trueCase, falseCase); - } -} -%$$ -For example, see -$cref/double CondExpOp/base_alloc.hpp/CondExpOp/$$. -For an example of and implementation of $code CondExpOp$$ with -a more involved $icode Base$$ type see -$cref/adolc CondExpOp/base_adolc.hpp/CondExpOp/$$. - - -$subhead Not Ordered$$ -If the type $icode Base$$ does not support ordering, -the $code CondExpOp$$ function does not make sense. -In this case one might (but need not) define $code CondExpOp$$ as follows: -$codei% -namespace CppAD { - inline %Base% CondExpOp( - enum CompareOp cop , - const %Base% &left , - const %Base% &right , - const %Base% &exp_if_true , - const %Base% &exp_if_false ) - { // attempt to use CondExp with a %Base% argument - assert(0); - return %Base%(0); - } -} -%$$ -For example, see -$cref/complex CondExpOp/base_complex.hpp/CondExpOp/$$. - -$head CondExpRel$$ -The macro invocation -$codei% - CPPAD_COND_EXP_REL(%Base%) -%$$ -uses $code CondExpOp$$ above to define the following functions -$codei% - CondExpLt(%left%, %right%, %exp_if_true%, %exp_if_false%) - CondExpLe(%left%, %right%, %exp_if_true%, %exp_if_false%) - CondExpEq(%left%, %right%, %exp_if_true%, %exp_if_false%) - CondExpGe(%left%, %right%, %exp_if_true%, %exp_if_false%) - CondExpGt(%left%, %right%, %exp_if_true%, %exp_if_false%) -%$$ -where the arguments have type $icode Base$$. -This should be done inside of the CppAD namespace. -For example, see -$cref/base_alloc/base_alloc.hpp/CondExpRel/$$. - -$end -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -/*! -\file base_cond_exp.hpp -CondExp operations that aid in meeting Base type requirements. -*/ - -/*! -\def CPPAD_COND_EXP_BASE_REL(Type, Rel, Op) -This macro defines the operation -\verbatim - CondExpRel(left, right, exp_if_true, exp_if_false) -\endverbatim -The argument \c Type is the \c Base type for this base require operation. -The argument \c Rel is one of \c Lt, \c Le, \c Eq, \c Ge, \c Gt. -The argument \c Op is the corresponding \c CompareOp value. -*/ -# define CPPAD_COND_EXP_BASE_REL(Type, Rel, Op) \ - inline Type CondExp##Rel( \ - const Type& left , \ - const Type& right , \ - const Type& exp_if_true , \ - const Type& exp_if_false ) \ - { return CondExpOp(Op, left, right, exp_if_true, exp_if_false); \ - } - -/*! -\def CPPAD_COND_EXP_REL(Type) -The macro defines the operations -\verbatim - CondExpLt(left, right, exp_if_true, exp_if_false) - CondExpLe(left, right, exp_if_true, exp_if_false) - CondExpEq(left, right, exp_if_true, exp_if_false) - CondExpGe(left, right, exp_if_true, exp_if_false) - CondExpGt(left, right, exp_if_true, exp_if_false) -\endverbatim -The argument \c Type is the \c Base type for this base require operation. -*/ -# define CPPAD_COND_EXP_REL(Type) \ - CPPAD_COND_EXP_BASE_REL(Type, Lt, CompareLt) \ - CPPAD_COND_EXP_BASE_REL(Type, Le, CompareLe) \ - CPPAD_COND_EXP_BASE_REL(Type, Eq, CompareEq) \ - CPPAD_COND_EXP_BASE_REL(Type, Ge, CompareGe) \ - CPPAD_COND_EXP_BASE_REL(Type, Gt, CompareGt) - -/*! -Template function to implement Conditional Expressions for simple types -that have comparision operators. - -\tparam CompareType -is the type of the left and right operands to the comparision operator. - -\tparam ResultType -is the type of the result, which is the same as \c CompareType except -during forward and reverse mode sparese calculations. - -\param cop -specifices which comparision to use; i.e., -$code <$$, -$code <=$$, -$code ==$$, -$code >=$$, -$code >$$, or -$code !=$$. - -\param left -is the left operand to the comparision operator. - -\param right -is the right operand to the comparision operator. - -\param exp_if_true -is the return value is the comparision results in true. - -\param exp_if_false -is the return value is the comparision results in false. - -\return -see \c exp_if_true and \c exp_if_false above. -*/ -template -ResultType CondExpTemplate( - enum CompareOp cop , - const CompareType& left , - const CompareType& right , - const ResultType& exp_if_true , - const ResultType& exp_if_false ) -{ ResultType returnValue; - switch( cop ) - { - case CompareLt: - if( left < right ) - returnValue = exp_if_true; - else returnValue = exp_if_false; - break; - - case CompareLe: - if( left <= right ) - returnValue = exp_if_true; - else returnValue = exp_if_false; - break; - - case CompareEq: - if( left == right ) - returnValue = exp_if_true; - else returnValue = exp_if_false; - break; - - case CompareGe: - if( left >= right ) - returnValue = exp_if_true; - else returnValue = exp_if_false; - break; - - case CompareGt: - if( left > right ) - returnValue = exp_if_true; - else returnValue = exp_if_false; - break; - - default: - CPPAD_ASSERT_UNKNOWN(0); - returnValue = exp_if_true; - } - return returnValue; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/base_double.hpp b/ct_core/include/ct/external/cppad/core/base_double.hpp deleted file mode 100644 index 63416fef8..000000000 --- a/ct_core/include/ct/external/cppad/core/base_double.hpp +++ /dev/null @@ -1,229 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_BASE_DOUBLE_HPP -# define CPPAD_CORE_BASE_DOUBLE_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include - -/* -$begin base_double.hpp$$ -$spell - namespaces - cppad - hpp - azmul - expm1 - atanh - acosh - asinh - erf - endif - abs_geq - acos - asin - atan - cos - sqrt - tanh - std - fabs - bool - Lt Le Eq Ge Gt - Rel - CppAD - CondExpOp - namespace - inline - enum - const - exp - const -$$ - - -$section Enable use of AD where Base is double$$ - -$head CondExpOp$$ -The type $code double$$ is a relatively simple type that supports -$code <$$, $code <=$$, $code ==$$, $code >=$$, and $code >$$ operators; see -$cref/ordered type/base_cond_exp/CondExpTemplate/Ordered Type/$$. -Hence its $code CondExpOp$$ function is defined by -$srccode%cpp% */ -namespace CppAD { - inline double CondExpOp( - enum CompareOp cop , - const double& left , - const double& right , - const double& exp_if_true , - const double& exp_if_false ) - { return CondExpTemplate(cop, left, right, exp_if_true, exp_if_false); - } -} -/* %$$ - -$head CondExpRel$$ -The $cref/CPPAD_COND_EXP_REL/base_cond_exp/CondExpRel/$$ macro invocation -$srccode%cpp% */ -namespace CppAD { - CPPAD_COND_EXP_REL(double) -} -/* %$$ -uses $code CondExpOp$$ above to -define $codei%CondExp%Rel%$$ for $code double$$ arguments -and $icode%Rel%$$ equal to -$code Lt$$, $code Le$$, $code Eq$$, $code Ge$$, and $code Gt$$. - -$head EqualOpSeq$$ -The type $code double$$ is simple (in this respect) and so we define -$srccode%cpp% */ -namespace CppAD { - inline bool EqualOpSeq(const double& x, const double& y) - { return x == y; } -} -/* %$$ - -$head Identical$$ -The type $code double$$ is simple (in this respect) and so we define -$srccode%cpp% */ -namespace CppAD { - inline bool IdenticalPar(const double& x) - { return true; } - inline bool IdenticalZero(const double& x) - { return (x == 0.); } - inline bool IdenticalOne(const double& x) - { return (x == 1.); } - inline bool IdenticalEqualPar(const double& x, const double& y) - { return (x == y); } -} -/* %$$ - -$head Integer$$ -$srccode%cpp% */ -namespace CppAD { - inline int Integer(const double& x) - { return static_cast(x); } -} -/* %$$ - -$head azmul$$ -$srccode%cpp% */ -namespace CppAD { - CPPAD_AZMUL( double ) -} -/* %$$ - -$head Ordered$$ -The $code double$$ type supports ordered comparisons -$srccode%cpp% */ -namespace CppAD { - inline bool GreaterThanZero(const double& x) - { return x > 0.; } - inline bool GreaterThanOrZero(const double& x) - { return x >= 0.; } - inline bool LessThanZero(const double& x) - { return x < 0.; } - inline bool LessThanOrZero(const double& x) - { return x <= 0.; } - inline bool abs_geq(const double& x, const double& y) - { return std::fabs(x) >= std::fabs(y); } -} -/* %$$ - -$head Unary Standard Math$$ -The following macro invocations import the $code double$$ versions of -the unary standard math functions into the $code CppAD$$ namespace. -Importing avoids ambiguity errors when using both the -$code CppAD$$ and $code std$$ namespaces. -Note this also defines the $cref/float/base_float.hpp/Unary Standard Math/$$ -versions of these functions. -$srccode%cpp% */ -namespace CppAD { - using std::acos; - using std::asin; - using std::atan; - using std::cos; - using std::cosh; - using std::exp; - using std::fabs; - using std::log; - using std::log10; - using std::sin; - using std::sinh; - using std::sqrt; - using std::tan; - using std::tanh; -# if CPPAD_USE_CPLUSPLUS_2011 - using std::erf; - using std::asinh; - using std::acosh; - using std::atanh; - using std::expm1; - using std::log1p; -# endif -} -/* %$$ -The absolute value function is special because its $code std$$ name is -$code fabs$$ -$srccode%cpp% */ -namespace CppAD { - inline double abs(const double& x) - { return std::fabs(x); } -} -/* %$$ - -$head sign$$ -The following defines the $code CppAD::sign$$ function that -is required to use $code AD$$: -$srccode%cpp% */ -namespace CppAD { - inline double sign(const double& x) - { if( x > 0. ) - return 1.; - if( x == 0. ) - return 0.; - return -1.; - } -} -/* %$$ - -$head pow$$ -The following defines a $code CppAD::pow$$ function that -is required to use $code AD$$. -As with the unary standard math functions, -this has the exact same signature as $code std::pow$$, -so use it instead of defining another function. -$srccode%cpp% */ -namespace CppAD { - using std::pow; -} -/* %$$ - -$head numeric_limits$$ -The following defines the CppAD $cref numeric_limits$$ -for the type $code double$$: -$srccode%cpp% */ -namespace CppAD { - CPPAD_NUMERIC_LIMITS(double, double) -} -/* %$$ - -$head to_string$$ -There is no need to define $code to_string$$ for $code double$$ -because it is defined by including $code cppad/utility/to_string.hpp$$; -see $cref to_string$$. -See $cref/base_complex.hpp/base_complex.hpp/to_string/$$ for an example where -it is necessary to define $code to_string$$ for a $icode Base$$ type. - -$end -*/ - -# endif diff --git a/ct_core/include/ct/external/cppad/core/base_float.hpp b/ct_core/include/ct/external/cppad/core/base_float.hpp deleted file mode 100644 index eb754bc8a..000000000 --- a/ct_core/include/ct/external/cppad/core/base_float.hpp +++ /dev/null @@ -1,230 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_BASE_FLOAT_HPP -# define CPPAD_CORE_BASE_FLOAT_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include - -/* -$begin base_float.hpp$$ -$spell - namespaces - cppad - hpp - azmul - expm1 - atanh - acosh - asinh - erf - endif - abs_geq - acos - asin - atan - cos - sqrt - tanh - std - fabs - bool - Lt Le Eq Ge Gt - Rel - CppAD - CondExpOp - namespace - inline - enum - const - exp - const -$$ - - -$section Enable use of AD where Base is float$$ - -$head CondExpOp$$ -The type $code float$$ is a relatively simple type that supports -$code <$$, $code <=$$, $code ==$$, $code >=$$, and $code >$$ operators; see -$cref/ordered type/base_cond_exp/CondExpTemplate/Ordered Type/$$. -Hence its $code CondExpOp$$ function is defined by -$srccode%cpp% */ -namespace CppAD { - inline float CondExpOp( - enum CompareOp cop , - const float& left , - const float& right , - const float& exp_if_true , - const float& exp_if_false ) - { return CondExpTemplate(cop, left, right, exp_if_true, exp_if_false); - } -} -/* %$$ - -$head CondExpRel$$ -The $cref/CPPAD_COND_EXP_REL/base_cond_exp/CondExpRel/$$ macro invocation -$srccode%cpp% */ -namespace CppAD { - CPPAD_COND_EXP_REL(float) -} -/* %$$ -uses $code CondExpOp$$ above to -define $codei%CondExp%Rel%$$ for $code float$$ arguments -and $icode%Rel%$$ equal to -$code Lt$$, $code Le$$, $code Eq$$, $code Ge$$, and $code Gt$$. - -$head EqualOpSeq$$ -The type $code float$$ is simple (in this respect) and so we define -$srccode%cpp% */ -namespace CppAD { - inline bool EqualOpSeq(const float& x, const float& y) - { return x == y; } -} -/* %$$ - -$head Identical$$ -The type $code float$$ is simple (in this respect) and so we define -$srccode%cpp% */ -namespace CppAD { - inline bool IdenticalPar(const float& x) - { return true; } - inline bool IdenticalZero(const float& x) - { return (x == 0.f); } - inline bool IdenticalOne(const float& x) - { return (x == 1.f); } - inline bool IdenticalEqualPar(const float& x, const float& y) - { return (x == y); } -} -/* %$$ - -$head Integer$$ -$srccode%cpp% */ -namespace CppAD { - inline int Integer(const float& x) - { return static_cast(x); } -} -/* %$$ - -$head azmul$$ -$srccode%cpp% */ -namespace CppAD { - CPPAD_AZMUL( float ) -} -/* %$$ - -$head Ordered$$ -The $code float$$ type supports ordered comparisons -$srccode%cpp% */ -namespace CppAD { - inline bool GreaterThanZero(const float& x) - { return x > 0.f; } - inline bool GreaterThanOrZero(const float& x) - { return x >= 0.f; } - inline bool LessThanZero(const float& x) - { return x < 0.f; } - inline bool LessThanOrZero(const float& x) - { return x <= 0.f; } - inline bool abs_geq(const float& x, const float& y) - { return std::fabs(x) >= std::fabs(y); } -} -/* %$$ - -$head Unary Standard Math$$ -The following macro invocations import the $code float$$ versions of -the unary standard math functions into the $code CppAD$$ namespace. -Importing avoids ambiguity errors when using both the -$code CppAD$$ and $code std$$ namespaces. -Note this also defines the $cref/double/base_double.hpp/Unary Standard Math/$$ -versions of these functions. -$srccode%cpp% */ -namespace CppAD { - using std::acos; - using std::asin; - using std::atan; - using std::cos; - using std::cosh; - using std::exp; - using std::fabs; - using std::log; - using std::log10; - using std::sin; - using std::sinh; - using std::sqrt; - using std::tan; - using std::tanh; -# if CPPAD_USE_CPLUSPLUS_2011 - using std::erf; - using std::asinh; - using std::acosh; - using std::atanh; - using std::expm1; - using std::log1p; -# endif -} - -/* %$$ -The absolute value function is special because its $code std$$ name is -$code fabs$$ -$srccode%cpp% */ -namespace CppAD { - inline float abs(const float& x) - { return std::fabs(x); } -} -/* %$$ - -$head sign$$ -The following defines the $code CppAD::sign$$ function that -is required to use $code AD$$: -$srccode%cpp% */ -namespace CppAD { - inline float sign(const float& x) - { if( x > 0.f ) - return 1.f; - if( x == 0.f ) - return 0.f; - return -1.f; - } -} -/* %$$ -$head pow$$ -The following defines a $code CppAD::pow$$ function that -is required to use $code AD$$. -As with the unary standard math functions, -this has the exact same signature as $code std::pow$$, -so use it instead of defining another function. -$srccode%cpp% */ -namespace CppAD { - using std::pow; -} -/* %$$ - -$head numeric_limits$$ -The following defines the CppAD $cref numeric_limits$$ -for the type $code float$$: -$srccode%cpp% */ -namespace CppAD { - CPPAD_NUMERIC_LIMITS(float, float) -} -/* %$$ - -$head to_string$$ -There is no need to define $code to_string$$ for $code float$$ -because it is defined by including $code cppad/utility/to_string.hpp$$; -see $cref to_string$$. -See $cref/base_complex.hpp/base_complex.hpp/to_string/$$ for an example where -it is necessary to define $code to_string$$ for a $icode Base$$ type. - -$end -*/ - - -# endif diff --git a/ct_core/include/ct/external/cppad/core/base_hash.hpp b/ct_core/include/ct/external/cppad/core/base_hash.hpp deleted file mode 100644 index 057a1b769..000000000 --- a/ct_core/include/ct/external/cppad/core/base_hash.hpp +++ /dev/null @@ -1,84 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_BASE_HASH_HPP -# define CPPAD_CORE_BASE_HASH_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin base_hash$$ -$spell - alloc - Cpp - adouble - valgrind - const - inline -$$ - -$section Base Type Requirements for Hash Coding Values$$ - -$head Syntax$$ -$icode%code% = hash_code(%x%)%$$ - -$head Purpose$$ -CppAD uses a table of $icode Base$$ type values when recording -$codei%AD<%Base%>%$$ operations. -A hashing function is used to reduce number of values stored in this table; -for example, it is not necessary to store the value 3.0 every -time it is used as a $cref/parameter/parvar/$$. - -$head Default$$ -The default hashing function works with the set of bits that correspond -to a $icode Base$$ value. -In most cases this works well, but in some cases -it does not. For example, in the -$cref base_adolc.hpp$$ case, an $code adouble$$ value can have -fields that are not initialized and $code valgrind$$ reported an error -when these are used to form the hash code. - -$head x$$ -This argument has prototype -$codei% - const %Base%& %x -%$$ -It is the value we are forming a hash code for. - -$head code$$ -The return value $icode code$$ has prototype -$codei% - unsigned short %code% -%$$ -It is the hash code corresponding to $icode x$$. This intention is the -commonly used values will have different hash codes. -The hash code must satisfy -$codei% - %code% < CPPAD_HASH_TABLE_SIZE -%$$ -so that it is a valid index into the hash code table. - -$head inline$$ -If you define this function, it should declare it to be $code inline$$, -so that you do not get multiple definitions from different compilation units. - -$head Example$$ -See the $code base_alloc$$ $cref/hash_code/base_alloc.hpp/hash_code/$$ -and the $code adouble$$ $cref/hash_code/base_adolc.hpp/hash_code/$$. - -$end -*/ - -/*! -\def CPPAD_HASH_TABLE_SIZE -the codes retruned by hash_code are between zero and CPPAD_HASH_TABLE_SIZE -minus one. -*/ -# define CPPAD_HASH_TABLE_SIZE 10000 - -# endif diff --git a/ct_core/include/ct/external/cppad/core/base_limits.hpp b/ct_core/include/ct/external/cppad/core/base_limits.hpp deleted file mode 100644 index 1b973cb58..000000000 --- a/ct_core/include/ct/external/cppad/core/base_limits.hpp +++ /dev/null @@ -1,67 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_BASE_LIMITS_HPP -# define CPPAD_CORE_BASE_LIMITS_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin base_limits$$ -$spell - std - namespace - CppAD -$$ - -$section Base Type Requirements for Numeric Limits$$ - -$head CppAD::numeric_limits$$ -A specialization for -$cref/CppAD::numeric_limits/numeric_limits/$$ -must be defined in order to use the type $codei%AD<%Base%>%$$. -CppAD does not use a specialization of -$codei%std::numeric_limits<%Base%>%$$. -Since C++11, using a specialization of -$codei%std::numeric_limits<%Base%>%$$ -would require that $icode Base$$ be a literal type. - -$head CPPAD_NUMERIC_LIMITS$$ -In most cases, this macro can be used to define the specialization where -the numeric limits for the type $icode Base$$ -are the same as the standard numeric limits for the type $icode Other$$. -For most $icode Base$$ types, -there is a choice of $icode Other$$, -for which the following preprocessor macro invocation suffices: -$codei% - namespace CppAD { - CPPAD_NUMERIC_LIMITS(%Other%, %Base%) - } -%$$ -where the macro is defined by -$srccode%cpp% */ -# define CPPAD_NUMERIC_LIMITS(Other, Base) \ -template <> class numeric_limits\ -{\ - public:\ - static Base min(void) \ - { return static_cast( std::numeric_limits::min() ); }\ - static Base max(void) \ - { return static_cast( std::numeric_limits::max() ); }\ - static Base epsilon(void) \ - { return static_cast( std::numeric_limits::epsilon() ); }\ - static Base quiet_NaN(void) \ - { return static_cast( std::numeric_limits::quiet_NaN() ); }\ -}; -/* %$$ -$end -*/ - -# endif diff --git a/ct_core/include/ct/external/cppad/core/base_std_math.hpp b/ct_core/include/ct/external/cppad/core/base_std_math.hpp deleted file mode 100644 index 9491c83e6..000000000 --- a/ct_core/include/ct/external/cppad/core/base_std_math.hpp +++ /dev/null @@ -1,186 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_BASE_STD_MATH_HPP -# define CPPAD_CORE_BASE_STD_MATH_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin base_std_math$$ -$spell - expm1 - atanh - acosh - asinh - inline - fabs - isnan - alloc - std - acos - asin - atan - cos - exp - sqrt - const - CppAD - namespace - erf -$$ - -$section Base Type Requirements for Standard Math Functions$$ - -$head Purpose$$ -These definitions are required for the user's code to use the type -$codei%AD<%Base%>%$$: - -$head Unary Standard Math$$ -The type $icode Base$$ must support the following functions -unary standard math functions (in the CppAD namespace): -$table -$bold Syntax$$ $cnext $bold Result$$ -$rnext -$icode%y% = abs(%x%)%$$ $cnext absolute value $rnext -$icode%y% = acos(%x%)%$$ $cnext inverse cosine $rnext -$icode%y% = asin(%x%)%$$ $cnext inverse sine $rnext -$icode%y% = atan(%x%)%$$ $cnext inverse tangent $rnext -$icode%y% = cos(%x%)%$$ $cnext cosine $rnext -$icode%y% = cosh(%x%)%$$ $cnext hyperbolic cosine $rnext -$icode%y% = exp(%x%)%$$ $cnext exponential $rnext -$icode%y% = fabs(%x%)%$$ $cnext absolute value $rnext -$icode%y% = log(%x%)%$$ $cnext natural logarithm $rnext -$icode%y% = sin(%x%)%$$ $cnext sine $rnext -$icode%y% = sinh(%x%)%$$ $cnext hyperbolic sine $rnext -$icode%y% = sqrt(%x%)%$$ $cnext square root $rnext -$icode%y% = tan(%x%)%$$ $cnext tangent -$tend -where the arguments and return value have the prototypes -$codei% - const %Base%& %x% - %Base% %y% -%$$ -For example, -$cref/base_alloc/base_alloc.hpp/Unary Standard Math/$$, - - -$head CPPAD_STANDARD_MATH_UNARY$$ -The macro invocation, within the CppAD namespace, -$codei% - CPPAD_STANDARD_MATH_UNARY(%Base%, %Fun%) -%$$ -defines the syntax -$codei% - %y% = CppAD::%Fun%(%x%) -%$$ -This macro uses the functions $codei%std::%Fun%$$ which -must be defined and have the same prototype as $codei%CppAD::%Fun%$$. -For example, -$cref/float/base_float.hpp/Unary Standard Math/$$. - -$head erf, asinh, acosh, atanh, expm1, log1p$$ -If this preprocessor symbol -$code CPPAD_USE_CPLUSPLUS_2011$$ is true ($code 1$$), -when compiling for c++11, the type -$code double$$ is supported for the functions listed below. -In this case, the type $icode Base$$ must also support these functions: -$table -$bold Syntax$$ $cnext $bold Result$$ -$rnext -$icode%y% = erf(%x%)%$$ $cnext error function $rnext -$icode%y% = asinh(%x%)%$$ $cnext inverse hyperbolic sin $rnext -$icode%y% = acosh(%x%)%$$ $cnext inverse hyperbolic cosine $rnext -$icode%y% = atanh(%x%)%$$ $cnext inverse hyperbolic tangent $rnext -$icode%y% = expm1(%x%)%$$ $cnext exponential of x minus one $rnext -$icode%y% = log1p(%x%)%$$ $cnext logarithm of one plus x -$tend -where the arguments and return value have the prototypes -$codei% - const %Base%& %x% - %Base% %y% -%$$ - -$head sign$$ -The type $icode Base$$ must support the syntax -$codei% - %y% = CppAD::sign(%x%) -%$$ -which computes -$latex \[ -y = \left\{ \begin{array}{ll} - +1 & {\rm if} \; x > 0 \\ - 0 & {\rm if} \; x = 0 \\ - -1 & {\rm if} \; x < 0 -\end{array} \right. -\] $$ -where $icode x$$ and $icode y$$ have the same prototype as above. -For example, see -$cref/base_alloc/base_alloc.hpp/sign/$$. -Note that, if ordered comparisons are not defined for the type $icode Base$$, -the $code code sign$$ function should generate an assert if it is used; see -$cref/complex invalid unary math/base_complex.hpp/Invalid Unary Math/$$. - -$head pow$$ -The type $icode Base$$ must support the syntax -$codei% - %z% = CppAD::pow(%x%, %y%) -%$$ -which computes $latex z = x^y$$. -The arguments $icode x$$ and $icode y$$ have prototypes -$codei% - const %Base%& %x% - const %Base%& %y% -%$$ -and the return value $icode z$$ has prototype -$codei% - %Base% %z% -%$$ -For example, see -$cref/base_alloc/base_alloc.hpp/pow/$$. - - -$head isnan$$ -If $icode Base$$ defines the $code isnan$$ function, -you may also have to provide a definition in the CppAD namespace -(to avoid a function ambiguity). -For example, see -$cref/base_complex/base_complex.hpp/isnan/$$. - - -$end -------------------------------------------------------------------------------- -*/ - -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -/*! -\file base_std_math.hpp -Defintions that aid meeting Base type requirements for standard math functions. -*/ - -/*! -\def CPPAD_STANDARD_MATH_UNARY(Type, Fun) -This macro defines the function -\verbatim - y = CppAD:Fun(x) -\endverbatim -where the argument \c x and return value \c y have type \c Type -using the corresponding function std::Fun. -*/ -# define CPPAD_STANDARD_MATH_UNARY(Type, Fun) \ - inline Type Fun(const Type& x) \ - { return std::Fun(x); } - -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/core/base_to_string.hpp b/ct_core/include/ct/external/cppad/core/base_to_string.hpp deleted file mode 100644 index 010528b05..000000000 --- a/ct_core/include/ct/external/cppad/core/base_to_string.hpp +++ /dev/null @@ -1,68 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_BASE_TO_STRING_HPP -# define CPPAD_CORE_BASE_TO_STRING_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin base_to_string$$ -$spell - std - namespace - CppAD - struct - const - stringstream - setprecision - str -$$ - -$section Extending to_string To Another Floating Point Type$$ - -$head Base Requirement$$ -If the function $cref to_string$$ is used by an -$cref/AD type above Base/glossary/AD Type Above Base/$$, -A specialization for the template structure -$code CppAD::to_string_struct$$ must be defined. - -$head CPPAD_TO_STRING$$ -For most $icode Base$$ types, -the following can be used to define the specialization: -$codei% - namespace CppAD { - CPPAD_TO_STRING(%Base%) - } -%$$ -Note that the $code CPPAD_TO_STRING$$ macro assumes that the -$cref base_limits$$ and $cref base_std_math$$ have already been defined -for this type. -This macro is defined as follows: -$srccode%cpp% */ -# define CPPAD_TO_STRING(Base) \ -template <> struct to_string_struct\ -{ std::string operator()(const Base& value) \ - { std::stringstream os;\ - Base epsilon = CppAD::numeric_limits::epsilon();\ - Base log10 = CppAD::log( epsilon ) / CppAD::log(Base(10.));\ - size_t n_digits = 1 - Integer( log10 );\ - os << std::setprecision(n_digits);\ - os << value;\ - return os.str();\ - }\ -}; -/* %$$ -$end ------------------------------------------------------------------------------- -*/ -// make sure to_string has been included -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/core/bender_quad.hpp b/ct_core/include/ct/external/cppad/core/bender_quad.hpp deleted file mode 100644 index 8aba1a247..000000000 --- a/ct_core/include/ct/external/cppad/core/bender_quad.hpp +++ /dev/null @@ -1,405 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_BENDER_QUAD_HPP -# define CPPAD_CORE_BENDER_QUAD_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin BenderQuad$$ -$spell - cppad.hpp - BAvector - gx - gxx - CppAD - Fy - dy - Jacobian - ADvector - const - dg - ddg -$$ - - -$section Computing Jacobian and Hessian of Bender's Reduced Objective$$ -$mindex BenderQuad$$ - -$head Syntax$$ -$codei% -# include -BenderQuad(%x%, %y%, %fun%, %g%, %gx%, %gxx%)%$$ - -$head See Also$$ -$cref opt_val_hes$$ - -$head Problem$$ -The type $cref/ADvector/BenderQuad/ADvector/$$ cannot be determined -form the arguments above -(currently the type $icode ADvector$$ must be -$codei%CPPAD_TESTVECTOR(%Base%)%$$.) -This will be corrected in the future by requiring $icode Fun$$ -to define $icode%Fun%::vector_type%$$ which will specify the -type $icode ADvector$$. - -$head Purpose$$ -We are given the optimization problem -$latex \[ -\begin{array}{rcl} -{\rm minimize} & F(x, y) & {\rm w.r.t.} \; (x, y) \in \B{R}^n \times \B{R}^m -\end{array} -\] $$ -that is convex with respect to $latex y$$. -In addition, we are given a set of equations $latex H(x, y)$$ -such that -$latex \[ - H[ x , Y(x) ] = 0 \;\; \Rightarrow \;\; F_y [ x , Y(x) ] = 0 -\] $$ -(In fact, it is often the case that $latex H(x, y) = F_y (x, y)$$.) -Furthermore, it is easy to calculate a Newton step for these equations; i.e., -$latex \[ - dy = - [ \partial_y H(x, y)]^{-1} H(x, y) -\] $$ -The purpose of this routine is to compute the -value, Jacobian, and Hessian of the reduced objective function -$latex \[ - G(x) = F[ x , Y(x) ] -\] $$ -Note that if only the value and Jacobian are needed, they can be -computed more quickly using the relations -$latex \[ - G^{(1)} (x) = \partial_x F [x, Y(x) ] -\] $$ - -$head x$$ -The $code BenderQuad$$ argument $icode x$$ has prototype -$codei% - const %BAvector% &%x% -%$$ -(see $cref/BAvector/BenderQuad/BAvector/$$ below) -and its size must be equal to $icode n$$. -It specifies the point at which we evaluating -the reduced objective function and its derivatives. - - -$head y$$ -The $code BenderQuad$$ argument $icode y$$ has prototype -$codei% - const %BAvector% &%y% -%$$ -and its size must be equal to $icode m$$. -It must be equal to $latex Y(x)$$; i.e., -it must solve the problem in $latex y$$ for this given value of $latex x$$ -$latex \[ -\begin{array}{rcl} - {\rm minimize} & F(x, y) & {\rm w.r.t.} \; y \in \B{R}^m -\end{array} -\] $$ - -$head fun$$ -The $code BenderQuad$$ object $icode fun$$ -must support the member functions listed below. -The $codei%AD<%Base%>%$$ arguments will be variables for -a tape created by a call to $cref Independent$$ from $code BenderQuad$$ -(hence they can not be combined with variables corresponding to a -different tape). - -$subhead fun.f$$ -The $code BenderQuad$$ argument $icode fun$$ supports the syntax -$codei% - %f% = %fun%.f(%x%, %y%) -%$$ -The $icode%fun%.f%$$ argument $icode x$$ has prototype -$codei% - const %ADvector% &%x% -%$$ -(see $cref/ADvector/BenderQuad/ADvector/$$ below) -and its size must be equal to $icode n$$. -The $icode%fun%.f%$$ argument $icode y$$ has prototype -$codei% - const %ADvector% &%y% -%$$ -and its size must be equal to $icode m$$. -The $icode%fun%.f%$$ result $icode f$$ has prototype -$codei% - %ADvector% %f% -%$$ -and its size must be equal to one. -The value of $icode f$$ is -$latex \[ - f = F(x, y) -\] $$. - -$subhead fun.h$$ -The $code BenderQuad$$ argument $icode fun$$ supports the syntax -$codei% - %h% = %fun%.h(%x%, %y%) -%$$ -The $icode%fun%.h%$$ argument $icode x$$ has prototype -$codei% - const %ADvector% &%x% -%$$ -and its size must be equal to $icode n$$. -The $icode%fun%.h%$$ argument $icode y$$ has prototype -$codei% - const %BAvector% &%y% -%$$ -and its size must be equal to $icode m$$. -The $icode%fun%.h%$$ result $icode h$$ has prototype -$codei% - %ADvector% %h% -%$$ -and its size must be equal to $icode m$$. -The value of $icode h$$ is -$latex \[ - h = H(x, y) -\] $$. - -$subhead fun.dy$$ -The $code BenderQuad$$ argument $icode fun$$ supports the syntax -$codei% - %dy% = %fun%.dy(%x%, %y%, %h%) - -%x% -%$$ -The $icode%fun%.dy%$$ argument $icode x$$ has prototype -$codei% - const %BAvector% &%x% -%$$ -and its size must be equal to $icode n$$. -Its value will be exactly equal to the $code BenderQuad$$ argument -$icode x$$ and values depending on it can be stored as private objects -in $icode f$$ and need not be recalculated. -$codei% - -%y% -%$$ -The $icode%fun%.dy%$$ argument $icode y$$ has prototype -$codei% - const %BAvector% &%y% -%$$ -and its size must be equal to $icode m$$. -Its value will be exactly equal to the $code BenderQuad$$ argument -$icode y$$ and values depending on it can be stored as private objects -in $icode f$$ and need not be recalculated. -$codei% - -%h% -%$$ -The $icode%fun%.dy%$$ argument $icode h$$ has prototype -$codei% - const %ADvector% &%h% -%$$ -and its size must be equal to $icode m$$. -$codei% - -%dy% -%$$ -The $icode%fun%.dy%$$ result $icode dy$$ has prototype -$codei% - %ADvector% %dy% -%$$ -and its size must be equal to $icode m$$. -The return value $icode dy$$ is given by -$latex \[ - dy = - [ \partial_y H (x , y) ]^{-1} h -\] $$ -Note that if $icode h$$ is equal to $latex H(x, y)$$, -$latex dy$$ is the Newton step for finding a zero -of $latex H(x, y)$$ with respect to $latex y$$; -i.e., -$latex y + dy$$ is an approximate solution for the equation -$latex H (x, y + dy) = 0$$. - -$head g$$ -The argument $icode g$$ has prototype -$codei% - %BAvector% &%g% -%$$ -and has size one. -The input value of its element does not matter. -On output, -it contains the value of $latex G (x)$$; i.e., -$latex \[ - g[0] = G (x) -\] $$ - -$head gx$$ -The argument $icode gx$$ has prototype -$codei% - %BAvector% &%gx% -%$$ -and has size $latex n $$. -The input values of its elements do not matter. -On output, -it contains the Jacobian of $latex G (x)$$; i.e., -for $latex j = 0 , \ldots , n-1$$, -$latex \[ - gx[ j ] = G^{(1)} (x)_j -\] $$ - -$head gxx$$ -The argument $icode gx$$ has prototype -$codei% - %BAvector% &%gxx% -%$$ -and has size $latex n \times n$$. -The input values of its elements do not matter. -On output, -it contains the Hessian of $latex G (x)$$; i.e., -for $latex i = 0 , \ldots , n-1$$, and -$latex j = 0 , \ldots , n-1$$, -$latex \[ - gxx[ i * n + j ] = G^{(2)} (x)_{i,j} -\] $$ - -$head BAvector$$ -The type $icode BAvector$$ must be a -$cref SimpleVector$$ class. -We use $icode Base$$ to refer to the type of the elements of -$icode BAvector$$; i.e., -$codei% - %BAvector%::value_type -%$$ - -$head ADvector$$ -The type $icode ADvector$$ must be a -$cref SimpleVector$$ class with elements of type -$codei%AD<%Base%>%$$; i.e., -$codei% - %ADvector%::value_type -%$$ -must be the same type as -$codei% - AD< %BAvector%::value_type > -%$$. - - -$head Example$$ -$children% - example/bender_quad.cpp -%$$ -The file -$cref bender_quad.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - - -$end ------------------------------------------------------------------------------ -*/ - -namespace CppAD { // BEGIN CppAD namespace - -template -void BenderQuad( - const BAvector &x , - const BAvector &y , - Fun fun , - BAvector &g , - BAvector &gx , - BAvector &gxx ) -{ // determine the base type - typedef typename BAvector::value_type Base; - - // check that BAvector is a SimpleVector class - CheckSimpleVector(); - - // declare the ADvector type - typedef CPPAD_TESTVECTOR(AD) ADvector; - - // size of the x and y spaces - size_t n = size_t(x.size()); - size_t m = size_t(y.size()); - - // check the size of gx and gxx - CPPAD_ASSERT_KNOWN( - g.size() == 1, - "BenderQuad: size of the vector g is not equal to 1" - ); - CPPAD_ASSERT_KNOWN( - size_t(gx.size()) == n, - "BenderQuad: size of the vector gx is not equal to n" - ); - CPPAD_ASSERT_KNOWN( - size_t(gxx.size()) == n * n, - "BenderQuad: size of the vector gxx is not equal to n * n" - ); - - // some temporary indices - size_t i, j; - - // variable versions x - ADvector vx(n); - for(j = 0; j < n; j++) - vx[j] = x[j]; - - // declare the independent variables - Independent(vx); - - // evaluate h = H(x, y) - ADvector h(m); - h = fun.h(vx, y); - - // evaluate dy (x) = Newton step as a function of x through h only - ADvector dy(m); - dy = fun.dy(x, y, h); - - // variable version of y - ADvector vy(m); - for(j = 0; j < m; j++) - vy[j] = y[j] + dy[j]; - - // evaluate G~ (x) = F [ x , y + dy(x) ] - ADvector gtilde(1); - gtilde = fun.f(vx, vy); - - // AD function object that corresponds to G~ (x) - // We will make heavy use of this tape, so optimize it - ADFun Gtilde; - Gtilde.Dependent(vx, gtilde); - Gtilde.optimize(); - - // value of G(x) - g = Gtilde.Forward(0, x); - - // initial forward direction vector as zero - BAvector dx(n); - for(j = 0; j < n; j++) - dx[j] = Base(0); - - // weight, first and second order derivative values - BAvector dg(1), w(1), ddw(2 * n); - w[0] = 1.; - - - // Jacobian and Hessian of G(x) is equal Jacobian and Hessian of Gtilde - for(j = 0; j < n; j++) - { // compute partials in x[j] direction - dx[j] = Base(1); - dg = Gtilde.Forward(1, dx); - gx[j] = dg[0]; - - // restore the dx vector to zero - dx[j] = Base(0); - - // compute second partials w.r.t x[j] and x[l] for l = 1, n - ddw = Gtilde.Reverse(2, w); - for(i = 0; i < n; i++) - gxx[ i * n + j ] = ddw[ i * 2 + 1 ]; - } - - return; -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/bool_fun.hpp b/ct_core/include/ct/external/cppad/core/bool_fun.hpp deleted file mode 100644 index 68bfd8ddc..000000000 --- a/ct_core/include/ct/external/cppad/core/bool_fun.hpp +++ /dev/null @@ -1,244 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_BOOL_FUN_HPP -# define CPPAD_CORE_BOOL_FUN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin BoolFun$$ -$spell - namespace - bool - CppAD - const -$$ - - -$section AD Boolean Functions$$ -$mindex bool CPPAD_BOOL_UNARY CPPAD_BOOL_BINARY$$ - -$head Syntax$$ -$codei%CPPAD_BOOL_UNARY(%Base%, %unary_name%) -%$$ -$icode%b% = %unary_name%(%u%) -%$$ -$icode%b% = %unary_name%(%x%) -%$$ -$codei%CPPAD_BOOL_BINARY(%Base%, %binary_name%) -%$$ -$icode%b% = %binary_name%(%u%, %v%) -%$$ -$icode%b% = %binary_name%(%x%, %y%)%$$ - - -$head Purpose$$ -Create a $code bool$$ valued function that has $codei%AD<%Base%>%$$ arguments. - -$head unary_name$$ -This is the name of the $code bool$$ valued function with one argument -(as it is used in the source code). -The user must provide a version of $icode unary_name$$ where -the argument has type $icode Base$$. -CppAD uses this to create a version of $icode unary_name$$ where the -argument has type $codei%AD<%Base%>%$$. - -$head u$$ -The argument $icode u$$ has prototype -$codei% - const %Base% &%u% -%$$ -It is the value at which the user provided version of $icode unary_name$$ -is to be evaluated. -It is also used for the first argument to the -user provided version of $icode binary_name$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const AD<%Base%> &%x% -%$$ -It is the value at which the CppAD provided version of $icode unary_name$$ -is to be evaluated. -It is also used for the first argument to the -CppAD provided version of $icode binary_name$$. - -$head b$$ -The result $icode b$$ has prototype -$codei% - bool %b% -%$$ - -$head Create Unary$$ -The preprocessor macro invocation -$codei% - CPPAD_BOOL_UNARY(%Base%, %unary_name%) -%$$ -defines the version of $icode unary_name$$ with a $codei%AD<%Base%>%$$ -argument. -This can with in a namespace -(not the $code CppAD$$ namespace) -but must be outside of any routine. - -$head binary_name$$ -This is the name of the $code bool$$ valued function with two arguments -(as it is used in the source code). -The user must provide a version of $icode binary_name$$ where -the arguments have type $icode Base$$. -CppAD uses this to create a version of $icode binary_name$$ where the -arguments have type $codei%AD<%Base%>%$$. - -$head v$$ -The argument $icode v$$ has prototype -$codei% - const %Base% &%v% -%$$ -It is the second argument to -the user provided version of $icode binary_name$$. - -$head y$$ -The argument $icode x$$ has prototype -$codei% - const AD<%Base%> &%y% -%$$ -It is the second argument to -the CppAD provided version of $icode binary_name$$. - -$head Create Binary$$ -The preprocessor macro invocation -$codei% - CPPAD_BOOL_BINARY(%Base%, %binary_name%) -%$$ -defines the version of $icode binary_name$$ with $codei%AD<%Base%>%$$ -arguments. -This can with in a namespace -(not the $code CppAD$$ namespace) -but must be outside of any routine. - - -$head Operation Sequence$$ -The result of this operation is not an -$cref/AD of Base/glossary/AD of Base/$$ object. -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Example$$ -$children% - example/bool_fun.cpp -%$$ -The file -$cref bool_fun.cpp$$ -contains an example and test of these operations. -It returns true if it succeeds and false otherwise. - -$head Deprecated 2007-07-31$$ -The preprocessor symbols $code CppADCreateUnaryBool$$ -and $code CppADCreateBinaryBool$$ are defined to be the same as -$code CPPAD_BOOL_UNARY$$ and $code CPPAD_BOOL_BINARY$$ respectively -(but their use is deprecated). - -$end -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file bool_fun.hpp -Routines and macros that implement functions from AD to bool. -*/ - -/*! -Macro that defines a unary function bool F(AD x) -using bool F(Base x). - -\param Base -base for the AD type of arguments to this unary bool valued function. - -\param unary_name -name of this unary function; i.e., \c F. -*/ -# define CPPAD_BOOL_UNARY(Base, unary_name) \ - inline bool unary_name (const CppAD::AD &x) \ - { \ - return CppAD::AD::UnaryBool(unary_name, x); \ - } - -/*! -Deprecated name for CPPAD_BOOL_UNARY -*/ -# define CppADCreateUnaryBool CPPAD_BOOL_UNARY - -/*! -Link a function name, and AD value pair to function call with base argument -and bool retrun value. - -\param FunName -is the name of the function that we are linking. - -\param x -is the argument where we are evaluating the function. -*/ -template -inline bool AD::UnaryBool( - bool FunName(const Base &x), - const AD &x -) -{ - return FunName(x.value_); -} - -/*! -Macro that defines a binary function bool F(AD x, AD y) -using bool F(Base x, Base y). - -\param Base -base for the AD type of arguments to this binary bool valued function. - -\param binary_name -name of this binary function; i.e., \c F. -*/ - -# define CPPAD_BOOL_BINARY(Base, binary_name) \ - inline bool binary_name ( \ - const CppAD::AD &x, const CppAD::AD &y) \ - { \ - return CppAD::AD::BinaryBool(binary_name, x, y); \ - } -/*! -Deprecated name for CPPAD_BOOL_BINARY -*/ -# define CppADCreateBinaryBool CPPAD_BOOL_BINARY - - -/*! -Link a function name, and two AD values to function call with base arguments -and bool retrun value. - -\param FunName -is the name of the function that we are linking. - -\param x -is the first argument where we are evaluating the function at. - -\param y -is the second argument where we are evaluating the function at. -*/ -template -inline bool AD::BinaryBool( - bool FunName(const Base &x, const Base &y), - const AD &x, const AD &y -) -{ - return FunName(x.value_, y.value_); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/bool_valued.hpp b/ct_core/include/ct/external/cppad/core/bool_valued.hpp deleted file mode 100644 index 2853f36d3..000000000 --- a/ct_core/include/ct/external/cppad/core/bool_valued.hpp +++ /dev/null @@ -1,50 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_BOOL_VALUED_HPP -# define CPPAD_CORE_BOOL_VALUED_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin BoolValued$$ -$spell - Bool -$$ - - -$section Bool Valued Operations and Functions with AD Arguments$$ - -$children% - cppad/core/compare.hpp% - cppad/core/near_equal_ext.hpp% - cppad/core/bool_fun.hpp% - cppad/core/par_var.hpp% - cppad/core/equal_op_seq.hpp -%$$ -$table -$rref Compare$$ -$rref NearEqualExt$$ -$rref BoolFun$$ -$rref ParVar$$ -$rref EqualOpSeq$$ -$tend - - -$end -*/ - -# include -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/core/capacity_order.hpp b/ct_core/include/ct/external/cppad/core/capacity_order.hpp deleted file mode 100644 index d17e5bc45..000000000 --- a/ct_core/include/ct/external/cppad/core/capacity_order.hpp +++ /dev/null @@ -1,260 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_CAPACITY_ORDER_HPP -# define CPPAD_CORE_CAPACITY_ORDER_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin capacity_order$$ -$spell - var - taylor_ - xq - yq -$$ - - -$section Controlling Taylor Coefficients Memory Allocation$$ -$mindex Forward capacity_order control$$ - -$head Syntax$$ -$icode%f%.capacity_order(%c%)%$$ - -$subhead See Also$$ -$cref seq_property$$ - -$head Purpose$$ -The Taylor coefficients calculated by $cref Forward$$ mode calculations -are retained in an $cref ADFun$$ object for subsequent use during -$cref Reverse$$ mode and higher order Forward mode calculations. -For example, a call to $cref/Forward/forward_order/$$ with the syntax -$codei% - %yq% = %f%.Forward(%q%, %xq%) -%$$ -where $icode%q% > 0%$$ and $code%xq%.size() == %f%.Domain()%$$, -uses the lower order Taylor coefficients and -computes the $th q$$ order Taylor coefficients for all -the variables in the operation sequence corresponding to $icode f$$. -The $code capacity_order$$ operation allows you to control that -amount of memory that is retained by an AD function object -(to hold $code Forward$$ results for subsequent calculations). - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ - -$head c$$ -The argument $icode c$$ has prototype -$codei% - size_t %c% -%$$ -It specifies the number of Taylor coefficient orders that are allocated -in the AD operation sequence corresponding to $icode f$$. - -$subhead Pre-Allocating Memory$$ -If you plan to make calls to $code Forward$$ with the maximum value of -$icode q$$ equal to $icode Q$$, -it should be faster to pre-allocate memory for these calls using -$codei% - %f%.capacity_order(%c%) -%$$ -with $icode c$$ equal to $latex Q + 1$$. -If you do no do this, $code Forward$$ will automatically allocate memory -and will copy the results to a larger buffer, when necessary. -$pre - -$$ -Note that each call to $cref Dependent$$ frees the old memory -connected to the function object and sets the corresponding -taylor capacity to zero. - -$subhead Freeing Memory$$ -If you no longer need the Taylor coefficients of order $icode q$$ -and higher (that are stored in $icode f$$), -you can reduce the memory allocated to $icode f$$ using -$codei% - %f%.capacity_order(%c%) -%$$ -with $icode c$$ equal to $icode q$$. -Note that, if $cref ta_hold_memory$$ is true, this memory is not actually -returned to the system, but rather held for future use by the same thread. - -$head Original State$$ -If $icode f$$ is $cref/constructed/FunConstruct/$$ with the syntax -$codei% - ADFun<%Base%> %f%(%x%, %y%) -%$$, -there is an implicit call to $cref forward_zero$$ with $icode xq$$ equal to -the value of the -$cref/independent variables/glossary/Tape/Independent Variable/$$ -when the AD operation sequence was recorded. -This corresponds to $icode%c% == 1%$$. - -$children% - example/capacity_order.cpp -%$$ -$head Example$$ -The file -$cref capacity_order.cpp$$ -contains an example and test of these operations. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file capacity_order.hpp -Control of number of orders allocated. -\} -*/ - -/*! -Control of number of orders and directions allocated. - -\tparam Base -The type used during the forward mode computations; i.e., the corresponding -recording of operations used the type AD. - -\param c -is the number of orders to allocate memory for. -If c == 0 then \c r must also be zero. -In this case num_order_taylor_, cap_order_taylor_, and num_direction_taylor_ -are all set to zero. -In addition, taylor_.free() is called. - -\param r -is the number of directions to allocate memory for. -If c == 1 then \c r must also be one. -In all cases, it must hold that - - r == num_direction_taylor_ || num_order_taylor <= 1 - -Upon return, num_direction_taylor_ is equal to r. - -\par num_order_taylor_ -The output value of num_order_taylor_ is the mininumum of its input -value and c. This minimum is the number of orders that are copied to the -new taylor coefficient buffer. - -\par num_direction_taylor_ -The output value of num_direction_taylor_ is equal to \c r. -*/ - -template -void ADFun::capacity_order(size_t c, size_t r) -{ // temporary indices - size_t i, k, ell; - - if( (c == cap_order_taylor_) & (r == num_direction_taylor_) ) - return; - - if( c == 0 ) - { CPPAD_ASSERT_UNKNOWN( r == 0 ); - taylor_.free(); - num_order_taylor_ = 0; - cap_order_taylor_ = 0; - num_direction_taylor_ = r; - return; - } - CPPAD_ASSERT_UNKNOWN(r==num_direction_taylor_ || num_order_taylor_<=1); - - // Allocate new taylor with requested number of orders and directions - size_t new_len = ( (c-1)*r + 1 ) * num_var_tape_; - local::pod_vector new_taylor; - new_taylor.extend(new_len); - - // number of orders to copy - size_t p = std::min(num_order_taylor_, c); - if( p > 0 ) - { - // old order capacity - size_t C = cap_order_taylor_; - - // old number of directions - size_t R = num_direction_taylor_; - - // copy the old data into the new matrix - CPPAD_ASSERT_UNKNOWN( p == 1 || r == R ); - for(i = 0; i < num_var_tape_; i++) - { // copy zero order - size_t old_index = ((C-1) * R + 1) * i + 0; - size_t new_index = ((c-1) * r + 1) * i + 0; - new_taylor[ new_index ] = taylor_[ old_index ]; - // copy higher orders - for(k = 1; k < p; k++) - { for(ell = 0; ell < R; ell++) - { old_index = ((C-1) * R + 1) * i + (k-1) * R + ell + 1; - new_index = ((c-1) * r + 1) * i + (k-1) * r + ell + 1; - new_taylor[ new_index ] = taylor_[ old_index ]; - } - } - } - } - - // replace taylor_ by new_taylor - taylor_.swap(new_taylor); - cap_order_taylor_ = c; - num_order_taylor_ = p; - num_direction_taylor_ = r; - - // note that the destructor for new_taylor will free the old taylor memory - return; -} - -/*! -User API control of number of orders allocated. - -\tparam Base -The type used during the forward mode computations; i.e., the corresponding -recording of operations used the type AD. - -\param c -is the number of orders to allocate memory for. -If c == 0, -num_order_taylor_, cap_order_taylor_, and num_direction_taylor_ -are all set to zero. -In addition, taylor_.free() is called. - -\par num_order_taylor_ -The output value of num_order_taylor_ is the mininumum of its input -value and c. This minimum is the number of orders that are copied to the -new taylor coefficient buffer. - -\par num_direction_taylor_ -If \c is zero (one), \c num_direction_taylor_ is set to zero (one). -Otherwise, if \c num_direction_taylor_ is zero, it is set to one. -Othwerwise, \c num_direction_taylor_ is not modified. -*/ - -template -void ADFun::capacity_order(size_t c) -{ size_t r; - if( (c == 0) | (c == 1) ) - { r = c; - capacity_order(c, r); - return; - } - r = num_direction_taylor_; - if( r == 0 ) - r = 1; - capacity_order(c, r); - return; -} - -} // END CppAD namespace - - -# endif diff --git a/ct_core/include/ct/external/cppad/core/check_for_nan.hpp b/ct_core/include/ct/external/cppad/core/check_for_nan.hpp deleted file mode 100644 index 44a537fb9..000000000 --- a/ct_core/include/ct/external/cppad/core/check_for_nan.hpp +++ /dev/null @@ -1,199 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_CHECK_FOR_NAN_HPP -# define CPPAD_CORE_CHECK_FOR_NAN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin check_for_nan$$ -$spell - std - vec - Cpp - const - bool - newline -$$ -$section Check an ADFun Object For Nan Results$$ - -$head Syntax$$ -$icode%f%.check_for_nan(%b%) -%$$ -$icode%b% = %f%.check_for_nan() -%$$ -$codei%get_check_for_nan(%vec%, %file%) -%$$ - -$head Debugging$$ -If $code NDEBUG$$ is not defined, and -the result of a $cref/forward/forward_order/$$ or $cref/reverse/reverse_any/$$ -calculation contains a $cref nan$$, -CppAD can halt with an error message. - -$head f$$ -For the syntax where $icode b$$ is an argument, -$icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -(see $codei%ADFun<%Base%>%$$ $cref/constructor/FunConstruct/$$). -For the syntax where $icode b$$ is the result, -$icode f$$ has prototype -$codei% - const ADFun<%Base%> %f% -%$$ - -$head b$$ -This argument or result has prototype -$codei% - bool %b% -%$$ -Future calls to $icode%f%.Forward%$$ will (will not) check for $code nan$$. -depending on if $icode b$$ is true (false). - -$head Default$$ -The value for this setting after construction of $icode f$$) is true. -The value of this setting is not affected by calling -$cref Dependent$$ for this function object. - -$head Error Message$$ -If this error is detected during zero order forward mode, -the values of the independent variables that resulted in the $code nan$$ -are written to a temporary binary file. -This is so that you can run the original source code with those values -to see what is causing the $code nan$$. - -$subhead vector_size$$ -The error message with contain the text -$codei%vector_size = %vector_size%$$ followed the newline character -$code '\n'$$. -The value of $icode vector_size$$ is the number of elements -in the independent vector. - -$subhead file_name$$ -The error message with contain the text -$codei%file_name = %file_name%$$ followed the newline character -$code '\n'$$. -The value of $icode file_name$$ is the name of the temporary file -that contains the dependent variable values. - -$subhead index$$ -The error message will contain the text -$codei%index = %index%$$ followed by the newline character $code '\n'$$. -The value of $icode index$$ is the lowest dependent variable index -that has the value $code nan$$. - -$head get_check_for_nan$$ -This routine can be used to get the independent variable -values that result in a $code nan$$. - -$subhead vec$$ -This argument has prototype -$codei% - CppAD::vector<%Base%>& %vec% -%$$ -It size must be equal to the corresponding value of -$cref/vector_size/check_for_nan/Error Message/vector_size/$$ -in the corresponding error message. -The input value of its elements does not matter. -Upon return, it will contain the values for the independent variables, -in the corresponding call to $cref Independent$$, -that resulted in the $code nan$$. -(Note that the call to $code Independent$$ uses an vector with elements -of type $codei%AD<%Base%>%$$ and $icode vec$$ has elements of type -$icode Base$$.) - -$subhead file$$ -This argument has prototype -$codei% - const std::string& %file% -%$$ -It must be the value of -$cref/file_name/check_for_nan/Error Message/file_name/$$ -in the corresponding error message. - -$head Example$$ -$children% - example/check_for_nan.cpp -%$$ -The file -$cref check_for_nan.cpp$$ -contains an example and test of these operations. -It returns true if it succeeds and false otherwise. - -$end -*/ - -# include -# include -# include - -# if CPPAD_HAS_MKSTEMP -# include -# include -# else -# if CPPAD_HAS_TMPNAM_S -# include -# else -# include -# endif -# endif - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -template -void put_check_for_nan(const CppAD::vector& vec, std::string& file_name) -{ - size_t char_size = sizeof(Base) * vec.size(); - const char* char_ptr = reinterpret_cast( vec.data() ); -# if CPPAD_HAS_MKSTEMP - char pattern[] = "/tmp/fileXXXXXX"; - int fd = mkstemp(pattern); - file_name = pattern; - write(fd, char_ptr, char_size); - close(fd); -# else -# if CPPAD_HAS_TMPNAM_S - std::vector name(L_tmpnam_s); - if( tmpnam_s( name.data(), L_tmpnam_s ) != 0 ) - { CPPAD_ASSERT_KNOWN( - false, - "Cannot create a temporary file name" - ); - } - file_name = name.data(); -# else - file_name = tmpnam( CPPAD_NULL ); -# endif - std::fstream file_out(file_name.c_str(), std::ios::out|std::ios::binary ); - file_out.write(char_ptr, char_size); - file_out.close(); -# endif - return; -} - -template -void get_check_for_nan(CppAD::vector& vec, const std::string& file_name) -{ // - size_t n = vec.size(); - size_t char_size = sizeof(Base) * n; - char* char_ptr = reinterpret_cast( vec.data() ); - // - std::fstream file_in(file_name.c_str(), std::ios::in|std::ios::binary ); - file_in.read(char_ptr, char_size); - // - return; -} - -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/core/checkpoint.hpp b/ct_core/include/ct/external/cppad/core/checkpoint.hpp deleted file mode 100644 index d5e74673f..000000000 --- a/ct_core/include/ct/external/cppad/core/checkpoint.hpp +++ /dev/null @@ -1,1058 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_CHECKPOINT_HPP -# define CPPAD_CORE_CHECKPOINT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file checkpoint.hpp -defining checkpoint functions. -*/ - -/* -$begin checkpoint$$ -$spell - sv - var - cppad.hpp - CppAD - checkpoint - checkpointing - algo - atom_fun - const - enum - bool - recomputed -$$ - -$section Checkpointing Functions$$ - -$head Syntax$$ -$codei%checkpoint<%Base%> %atom_fun%( - %name%, %algo%, %ax%, %ay%, %sparsity%, %optimize% -) -%sv% = %atom_fun%.size_var() -%atom_fun%.option(%option_value%) -%algo%(%ax%, %ay%) -%atom_fun%(%ax%, %ay%) -checkpoint<%Base%>::clear()%$$ - -$head See Also$$ -$cref reverse_checkpoint.cpp$$ - -$head Purpose$$ - -$subhead Reduce Memory$$ -You can reduce the size of the tape and memory required for AD by -checkpointing functions of the form $latex y = f(x)$$ where -$latex f : B^n \rightarrow B^m$$. - -$subhead Faster Recording$$ -It may also reduce the time to make a recording the same function -for different values of the independent variable. -Note that the operation sequence for a recording that uses $latex f(x)$$ -may depend on its independent variables. - -$subhead Repeating Forward$$ -Normally, CppAD store $cref forward$$ mode results until they freed -using $cref capacity_order$$ or the corresponding $cref ADFun$$ object is -deleted. This is not true for checkpoint functions because a checkpoint -function may be used repeatedly with different arguments in the same tape. -Thus, forward mode results are recomputed each time a checkpoint function -is used during a forward or reverse mode sweep. - -$subhead Restriction$$ -The $cref/operation sequence/glossary/Operation/Sequence/$$ -representing $latex f(x)$$ cannot depend on the value of $latex x$$. -The approach in the $cref reverse_checkpoint.cpp$$ example case be applied -when the operation sequence depends on $latex x$$. - -$subhead Multiple Level AD$$ -If $icode Base$$ is an AD type, it is possible to record $icode Base$$ -operations. -Note that $icode atom_fun$$ will treat $icode algo$$ as an atomic -operation while recording $codei%AD%<%Base%>%$$ operations, but not while -recording $icode Base$$ operations. -See the $cref atomic_mul_level.cpp$$ example. - - -$head Method$$ -The $code checkpoint$$ class is derived from $code atomic_base$$ -and makes this easy. -It implements all the $code atomic_base$$ -$cref/virtual functions/atomic_base/Virtual Functions/$$ -and hence its source code $code cppad/core/checkpoint.hpp$$ -provides an example implementation of $cref atomic_base$$. -The difference is that $code checkpoint.hpp$$ uses AD -instead of user provided derivatives. - -$head constructor$$ -The syntax for the checkpoint constructor is -$codei% - checkpoint<%Base%> %atom_fun%(%name%, %algo%, %ax%, %ay%) -%$$ -$list number$$ -This constructor cannot be called in $cref/parallel/ta_in_parallel/$$ mode. -$lnext -You cannot currently be recording -$codei%AD<%Base%>%$$ operations when the constructor is called. -$lnext -This object $icode atom_fun$$ must not be destructed for as long -as any $codei%ADFun<%Base%>%$$ object uses its atomic operation. -$lnext -This class is implemented as a derived class of -$cref/atomic_base/atomic_ctor/atomic_base/$$ and hence -some of its error message will refer to $code atomic_base$$. -$lend - -$head Base$$ -The type $icode Base$$ specifies the base type for AD operations. - -$head ADVector$$ -The type $icode ADVector$$ must be a -$cref/simple vector class/SimpleVector/$$ with elements of type -$codei%AD<%Base%>%$$. - -$head name$$ -This $icode checkpoint$$ constructor argument has prototype -$codei% - const char* %name% -%$$ -It is the name used for error reporting. -The suggested value for $icode name$$ is $icode atom_fun$$; i.e., -the same name as used for the object being constructed. - -$head ax$$ -This argument has prototype -$codei% - const %ADVector%& %ax% -%$$ -and size must be equal to $icode n$$. -It specifies vector $latex x \in B^n$$ -at which an $codei%AD<%Base%>%$$ version of -$latex y = f(x)$$ is to be evaluated. - -$head ay$$ -This argument has prototype -$codei% - %ADVector%& %ay% -%$$ -Its input size must be equal to $icode m$$ and does not change. -The input values of its elements do not matter. -Upon return, it is an $codei%AD<%Base%>%$$ version of -$latex y = f(x)$$. - -$head sparsity$$ -This argument has prototype -$codei% - atomic_base<%Base%>::option_enum %sparsity% -%$$ -It specifies $cref/sparsity/atomic_ctor/atomic_base/sparsity/$$ -in the $code atomic_base$$ constructor and must be either -$codei%atomic_base<%Base%>::pack_sparsity_enum%$$, -$codei%atomic_base<%Base%>::bool_sparsity_enum%$$, or -$codei%atomic_base<%Base%>::set_sparsity_enum%$$. -This argument is optional and its default value is unspecified. - -$head optimize$$ -This argument has prototype -$codei% - bool %optimize% -%$$ -It specifies if the recording corresponding to the atomic function -should be $cref/optimized/optimize/$$. -One expects to use a checkpoint function many times, so it should -be worth the time to optimize its operation sequence. -For debugging purposes, it may be useful to use the -original operation sequence (before optimization) -because it corresponds more closely to $icode algo$$. -This argument is optional and its default value is true. - - -$head size_var$$ -This $code size_var$$ member function return value has prototype -$codei% - size_t %sv% -%$$ -It is the $cref/size_var/seq_property/size_var/$$ for the -$codei%ADFun<%Base%>%$$ object is used to store the operation sequence -corresponding to $icode algo$$. - -$head option$$ -The $code option$$ syntax can be used to set the type of sparsity -pattern used by $icode atom_fun$$. -This is an $codei%atomic_base<%Base%>%$$ function and its documentation -can be found at $cref atomic_option$$. - -$head algo$$ -The type of $icode algo$$ is arbitrary, except for the fact that -the syntax -$codei% - %algo%(%ax%, %ay%) -%$$ -must evaluate the function $latex y = f(x)$$ using -$codei%AD<%Base%>%$$ operations. -In addition, we assume that the -$cref/operation sequence/glossary/Operation/Sequence/$$ -does not depend on the value of $icode ax$$. - -$head atom_fun$$ -Given $icode ax$$ it computes the corresponding value of $icode ay$$ -using the operation sequence corresponding to $icode algo$$. -If $codei%AD<%Base%>%$$ operations are being recorded, -it enters the computation as single operation in the recording -see $cref/start recording/Independent/Start Recording/$$. -(Currently each use of $icode atom_fun$$ actually corresponds to -$icode%m%+%n%+2%$$ operations and creates $icode m$$ new variables, -but this is not part of the CppAD specifications and my change.) - -$head clear$$ -The $code atomic_base$$ class holds onto static work space in order to -increase speed by avoiding system memory allocation calls. -This call makes to work space $cref/available/ta_available/$$ to -for other uses by the same thread. -This should be called when you are done using the -user atomic functions for a specific value of $icode Base$$. - -$subhead Restriction$$ -The $code clear$$ routine cannot be called -while in $cref/parallel/ta_in_parallel/$$ execution mode. - -$children%example/atomic/checkpoint.cpp - %example/atomic/mul_level.cpp - %example/atomic/ode.cpp - %example/atomic/extended_ode.cpp -%$$ -$head Example$$ -The file $cref checkpoint.cpp$$ contains an example and test -of these operations. -It returns true if it succeeds and false if it fails. - -$end -*/ -template -class checkpoint : public atomic_base { -// --------------------------------------------------------------------------- -private: - /// same as option_enum in base class - typedef typename atomic_base::option_enum option_enum; - // - /// AD function corresponding to this checkpoint object - ADFun f_; - // - /// sparsity for entire Jacobian f(x)^{(1)} does not change so can cache it - local::sparse_list jac_sparse_set_; - vectorBool jac_sparse_bool_; - // - /// sparsity for sum_i f_i(x)^{(2)} does not change so can cache it - local::sparse_list hes_sparse_set_; - vectorBool hes_sparse_bool_; - // ------------------------------------------------------------------------ - option_enum sparsity(void) - { return static_cast< atomic_base* >(this)->sparsity(); } - // ------------------------------------------------------------------------ - /// set jac_sparse_set_ - void set_jac_sparse_set(void) - { CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.n_set() == 0 ); - bool transpose = false; - bool dependency = true; - size_t n = f_.Domain(); - size_t m = f_.Range(); - // Use the choice for forward / reverse that results in smaller - // size for the sparsity pattern of all variables in the tape. - if( n <= m ) - { local::sparse_list identity; - identity.resize(n, n); - for(size_t j = 0; j < n; j++) - identity.add_element(j, j); - f_.ForSparseJacCheckpoint( - n, identity, transpose, dependency, jac_sparse_set_ - ); - f_.size_forward_set(0); - } - else - { local::sparse_list identity; - identity.resize(m, m); - for(size_t i = 0; i < m; i++) - identity.add_element(i, i); - f_.RevSparseJacCheckpoint( - m, identity, transpose, dependency, jac_sparse_set_ - ); - } - CPPAD_ASSERT_UNKNOWN( f_.size_forward_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( f_.size_forward_bool() == 0 ); - } - /// set jac_sparse_bool_ - void set_jac_sparse_bool(void) - { CPPAD_ASSERT_UNKNOWN( jac_sparse_bool_.size() == 0 ); - bool transpose = false; - bool dependency = true; - size_t n = f_.Domain(); - size_t m = f_.Range(); - // Use the choice for forward / reverse that results in smaller - // size for the sparsity pattern of all variables in the tape. - if( n <= m ) - { vectorBool identity(n * n); - for(size_t j = 0; j < n; j++) - { for(size_t i = 0; i < n; i++) - identity[ i * n + j ] = (i == j); - } - jac_sparse_bool_ = f_.ForSparseJac( - n, identity, transpose, dependency - ); - f_.size_forward_bool(0); - } - else - { vectorBool identity(m * m); - for(size_t j = 0; j < m; j++) - { for(size_t i = 0; i < m; i++) - identity[ i * m + j ] = (i == j); - } - jac_sparse_bool_ = f_.RevSparseJac( - m, identity, transpose, dependency - ); - } - CPPAD_ASSERT_UNKNOWN( f_.size_forward_bool() == 0 ); - CPPAD_ASSERT_UNKNOWN( f_.size_forward_set() == 0 ); - } - // ------------------------------------------------------------------------ - /// set hes_sparse_set_ - void set_hes_sparse_set(void) - { CPPAD_ASSERT_UNKNOWN( hes_sparse_set_.n_set() == 0 ); - size_t n = f_.Domain(); - size_t m = f_.Range(); - // - // set version of sparsity for vector of all ones - vector all_one(m); - for(size_t i = 0; i < m; i++) - all_one[i] = true; - - // set version of sparsity for n by n idendity matrix - local::sparse_list identity; - identity.resize(n, n); - for(size_t j = 0; j < n; j++) - identity.add_element(j, j); - - // compute sparsity pattern for H(x) = sum_i f_i(x)^{(2)} - bool transpose = false; - bool dependency = false; - f_.ForSparseJacCheckpoint( - n, identity, transpose, dependency, jac_sparse_set_ - ); - f_.RevSparseHesCheckpoint( - n, all_one, transpose, hes_sparse_set_ - ); - CPPAD_ASSERT_UNKNOWN( hes_sparse_set_.n_set() == n ); - CPPAD_ASSERT_UNKNOWN( hes_sparse_set_.end() == n ); - // - // drop the forward sparsity results from f_ - f_.size_forward_set(0); - } - /// set hes_sparse_bool_ - void set_hes_sparse_bool(void) - { CPPAD_ASSERT_UNKNOWN( hes_sparse_bool_.size() == 0 ); - size_t n = f_.Domain(); - size_t m = f_.Range(); - // - // set version of sparsity for vector of all ones - vectorBool all_one(m); - for(size_t i = 0; i < m; i++) - all_one[i] = true; - - // set version of sparsity for n by n idendity matrix - vectorBool identity(n * n); - for(size_t j = 0; j < n; j++) - { for(size_t i = 0; i < n; i++) - identity[ i * n + j ] = (i == j); - } - - // compute sparsity pattern for H(x) = sum_i f_i(x)^{(2)} - bool transpose = false; - bool dependency = false; - f_.ForSparseJac(n, identity, transpose, dependency); - hes_sparse_bool_ = f_.RevSparseHes(n, all_one, transpose); - CPPAD_ASSERT_UNKNOWN( hes_sparse_bool_.size() == n * n ); - // - // drop the forward sparsity results from f_ - f_.size_forward_bool(0); - CPPAD_ASSERT_UNKNOWN( f_.size_forward_bool() == 0 ); - CPPAD_ASSERT_UNKNOWN( f_.size_forward_set() == 0 ); - } - // ------------------------------------------------------------------------ - /*! - Link from user_atomic to forward sparse Jacobian pack and bool - - \copydetails atomic_base::for_sparse_jac - */ - template - bool for_sparse_jac( - size_t q , - const sparsity_type& r , - sparsity_type& s , - const vector& x ) - { // during user sparsity calculations - size_t m = f_.Range(); - size_t n = f_.Domain(); - if( jac_sparse_bool_.size() == 0 ) - set_jac_sparse_bool(); - if( jac_sparse_set_.n_set() != 0 ) - jac_sparse_set_.resize(0, 0); - CPPAD_ASSERT_UNKNOWN( jac_sparse_bool_.size() == m * n ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.n_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( r.size() == n * q ); - CPPAD_ASSERT_UNKNOWN( s.size() == m * q ); - // - bool ok = true; - for(size_t i = 0; i < m; i++) - { for(size_t k = 0; k < q; k++) - s[i * q + k] = false; - } - // sparsity for s = jac_sparse_bool_ * r - for(size_t i = 0; i < m; i++) - { for(size_t k = 0; k < q; k++) - { // initialize sparsity for S(i,k) - bool s_ik = false; - // S(i,k) = sum_j J(i,j) * R(j,k) - for(size_t j = 0; j < n; j++) - { bool J_ij = jac_sparse_bool_[ i * n + j]; - bool R_jk = r[j * q + k ]; - s_ik |= ( J_ij & R_jk ); - } - s[i * q + k] = s_ik; - } - } - return ok; - } - // ------------------------------------------------------------------------ - /*! - Link from user_atomic to reverse sparse Jacobian pack and bool - - \copydetails atomic_base::rev_sparse_jac - */ - template - bool rev_sparse_jac( - size_t q , - const sparsity_type& rt , - sparsity_type& st , - const vector& x ) - { // during user sparsity calculations - size_t m = f_.Range(); - size_t n = f_.Domain(); - if( jac_sparse_bool_.size() == 0 ) - set_jac_sparse_bool(); - if( jac_sparse_set_.n_set() != 0 ) - jac_sparse_set_.resize(0, 0); - CPPAD_ASSERT_UNKNOWN( jac_sparse_bool_.size() == m * n ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.n_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( rt.size() == m * q ); - CPPAD_ASSERT_UNKNOWN( st.size() == n * q ); - bool ok = true; - // - // S = R * J where J is jacobian - for(size_t i = 0; i < q; i++) - { for(size_t j = 0; j < n; j++) - { // initialize sparsity for S(i,j) - bool s_ij = false; - // S(i,j) = sum_k R(i,k) * J(k,j) - for(size_t k = 0; k < m; k++) - { // sparsity for R(i, k) - bool R_ik = rt[ k * q + i ]; - bool J_kj = jac_sparse_bool_[ k * n + j ]; - s_ij |= (R_ik & J_kj); - } - // set sparsity for S^T - st[ j * q + i ] = s_ij; - } - } - return ok; - } - /*! - Link from user_atomic to reverse sparse Hessian bools - - \copydetails atomic_base::rev_sparse_hes - */ - template - bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const sparsity_type& r , - const sparsity_type& u , - sparsity_type& v , - const vector& x ) - { size_t n = f_.Domain(); -# ifndef NDEBUG - size_t m = f_.Range(); -# endif - CPPAD_ASSERT_UNKNOWN( vx.size() == n ); - CPPAD_ASSERT_UNKNOWN( s.size() == m ); - CPPAD_ASSERT_UNKNOWN( t.size() == n ); - CPPAD_ASSERT_UNKNOWN( r.size() == n * q ); - CPPAD_ASSERT_UNKNOWN( u.size() == m * q ); - CPPAD_ASSERT_UNKNOWN( v.size() == n * q ); - // - bool ok = true; - - // make sure hes_sparse_bool_ has been set - if( hes_sparse_bool_.size() == 0 ) - set_hes_sparse_bool(); - if( hes_sparse_set_.n_set() != 0 ) - hes_sparse_set_.resize(0, 0); - CPPAD_ASSERT_UNKNOWN( hes_sparse_bool_.size() == n * n ); - CPPAD_ASSERT_UNKNOWN( hes_sparse_set_.n_set() == 0 ); - - - // compute sparsity pattern for T(x) = S(x) * f'(x) - t = f_.RevSparseJac(1, s); -# ifndef NDEBUG - for(size_t j = 0; j < n; j++) - CPPAD_ASSERT_UNKNOWN( vx[j] || ! t[j] ) -# endif - - // V(x) = f'(x)^T * g''(y) * f'(x) * R + g'(y) * f''(x) * R - // U(x) = g''(y) * f'(x) * R - // S(x) = g'(y) - - // compute sparsity pattern for A(x) = f'(x)^T * U(x) - bool transpose = true; - sparsity_type a(n * q); - a = f_.RevSparseJac(q, u, transpose); - - // Need sparsity pattern for H(x) = (S(x) * f(x))''(x) * R, - // but use less efficient sparsity for f(x)''(x) * R so that - // hes_sparse_set_ can be used every time this is needed. - for(size_t i = 0; i < n; i++) - { for(size_t k = 0; k < q; k++) - { // initialize sparsity pattern for H(i,k) - bool h_ik = false; - // H(i,k) = sum_j f''(i,j) * R(j,k) - for(size_t j = 0; j < n; j++) - { bool f_ij = hes_sparse_bool_[i * n + j]; - bool r_jk = r[j * q + k]; - h_ik |= ( f_ij & r_jk ); - } - // sparsity for H(i,k) - v[i * q + k] = h_ik; - } - } - - // compute sparsity pattern for V(x) = A(x) + H(x) - for(size_t i = 0; i < n; i++) - { for(size_t k = 0; k < q; k++) - // v[ i * q + k ] |= a[ i * q + k]; - v[ i * q + k ] = bool(v[ i * q + k]) | bool(a[ i * q + k]); - } - return ok; - } -public: - // ------------------------------------------------------------------------ - /*! - Constructor of a checkpoint object - - \param name [in] - is the user's name for the AD version of this atomic operation. - - \param algo [in/out] - user routine that compute AD function values - (not const because state may change during evaluation). - - \param ax [in] - argument value where algo operation sequence is taped. - - \param ay [out] - function value at specified argument value. - - \param sparsity [in] - what type of sparsity patterns are computed by this function, - pack_sparsity_enum bool_sparsity_enum, or set_sparsity_enum. - The default value is unspecified. - - \param optimize [in] -l should the operation sequence corresponding to the algo be optimized. - The default value is true, but it is - sometimes useful to use false for debugging purposes. - */ - template - checkpoint( - const char* name , - Algo& algo , - const ADVector& ax , - ADVector& ay , - option_enum sparsity = - atomic_base::pack_sparsity_enum , - bool optimize = true - ) : atomic_base(name, sparsity) - { CheckSimpleVector< CppAD::AD , ADVector>(); - - // make a copy of ax because Independent modifies AD information - ADVector x_tmp(ax); - // delcare x_tmp as the independent variables - Independent(x_tmp); - // record mapping from x_tmp to ay - algo(x_tmp, ay); - // create function f_ : x -> y - f_.Dependent(ay); - if( optimize ) - { // suppress checking for nan in f_ results - // (see optimize documentation for atomic functions) - f_.check_for_nan(false); - // - // now optimize - f_.optimize(); - } - // now disable checking of comparison operations - // 2DO: add a debugging mode that checks for changes and aborts - f_.compare_change_count(0); - } - // ------------------------------------------------------------------------ - /*! - Implement the user call to atom_fun.size_var(). - */ - size_t size_var(void) - { return f_.size_var(); } - // ------------------------------------------------------------------------ - /*! - Implement the user call to atom_fun(ax, ay). - - \tparam ADVector - A simple vector class with elements of type AD. - - \param id - optional parameter which must be zero if present. - - \param ax - is the argument vector for this call, - ax.size() determines the number of arguments. - - \param ay - is the result vector for this call, - ay.size() determines the number of results. - */ - template - void operator()(const ADVector& ax, ADVector& ay, size_t id = 0) - { CPPAD_ASSERT_KNOWN( - id == 0, - "checkpoint: id is non-zero in atom_fun(ax, ay, id)" - ); - this->atomic_base::operator()(ax, ay, id); - } - // ------------------------------------------------------------------------ - /*! - Link from user_atomic to forward mode - - \copydetails atomic_base::forward - */ - virtual bool forward( - size_t p , - size_t q , - const vector& vx , - vector& vy , - const vector& tx , - vector& ty ) - { size_t n = f_.Domain(); - size_t m = f_.Range(); - // - CPPAD_ASSERT_UNKNOWN( f_.size_var() > 0 ); - CPPAD_ASSERT_UNKNOWN( tx.size() % (q+1) == 0 ); - CPPAD_ASSERT_UNKNOWN( ty.size() % (q+1) == 0 ); - CPPAD_ASSERT_UNKNOWN( n == tx.size() / (q+1) ); - CPPAD_ASSERT_UNKNOWN( m == ty.size() / (q+1) ); - bool ok = true; - // - if( vx.size() == 0 ) - { // during user forward mode - if( jac_sparse_set_.n_set() != 0 ) - jac_sparse_set_.resize(0,0); - if( jac_sparse_bool_.size() != 0 ) - jac_sparse_bool_.clear(); - // - if( hes_sparse_set_.n_set() != 0 ) - hes_sparse_set_.resize(0,0); - if( hes_sparse_bool_.size() != 0 ) - hes_sparse_bool_.clear(); - } - if( vx.size() > 0 ) - { // need Jacobian sparsity pattern to determine variable relation - // during user recording using checkpoint functions - if( sparsity() == atomic_base::set_sparsity_enum ) - { if( jac_sparse_set_.n_set() == 0 ) - set_jac_sparse_set(); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.n_set() == m ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.end() == n ); - // - for(size_t i = 0; i < m; i++) - { vy[i] = false; - local::sparse_list::const_iterator set_itr(jac_sparse_set_, i); - size_t j = *set_itr; - while(j < n ) - { // y[i] depends on the value of x[j] - // cast avoid Microsoft warning (should not be needed) - vy[i] |= static_cast( vx[j] ); - j = *(++set_itr); - } - } - } - else - { if( jac_sparse_set_.n_set() != 0 ) - jac_sparse_set_.resize(0, 0); - if( jac_sparse_bool_.size() == 0 ) - set_jac_sparse_bool(); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.n_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_bool_.size() == m * n ); - // - for(size_t i = 0; i < m; i++) - { vy[i] = false; - for(size_t j = 0; j < n; j++) - { if( jac_sparse_bool_[ i * n + j ] ) - { // y[i] depends on the value of x[j] - // cast avoid Microsoft warning - vy[i] |= static_cast( vx[j] ); - } - } - } - } - } - // compute forward results for orders zero through q - ty = f_.Forward(q, tx); - - // no longer need the Taylor coefficients in f_ - // (have to reconstruct them every time) - // Hold onto sparsity pattern because it is always good. - size_t c = 0; - size_t r = 0; - f_.capacity_order(c, r); - return ok; - } - // ------------------------------------------------------------------------ - /*! - Link from user_atomic to reverse mode - - \copydetails atomic_base::reverse - */ - virtual bool reverse( - size_t q , - const vector& tx , - const vector& ty , - vector& px , - const vector& py ) - { -# ifndef NDEBUG - size_t n = f_.Domain(); - size_t m = f_.Range(); -# endif - CPPAD_ASSERT_UNKNOWN( n == tx.size() / (q+1) ); - CPPAD_ASSERT_UNKNOWN( m == ty.size() / (q+1) ); - CPPAD_ASSERT_UNKNOWN( f_.size_var() > 0 ); - CPPAD_ASSERT_UNKNOWN( tx.size() % (q+1) == 0 ); - CPPAD_ASSERT_UNKNOWN( ty.size() % (q+1) == 0 ); - bool ok = true; - - // put proper forward mode coefficients in f_ -# ifdef NDEBUG - // compute forward results for orders zero through q - f_.Forward(q, tx); -# else - CPPAD_ASSERT_UNKNOWN( px.size() == n * (q+1) ); - CPPAD_ASSERT_UNKNOWN( py.size() == m * (q+1) ); - size_t i, j, k; - // - // compute forward results for orders zero through q - vector check_ty = f_.Forward(q, tx); - for(i = 0; i < m; i++) - { for(k = 0; k <= q; k++) - { j = i * (q+1) + k; - CPPAD_ASSERT_UNKNOWN( check_ty[j] == ty[j] ); - } - } -# endif - // now can run reverse mode - px = f_.Reverse(q+1, py); - - // no longer need the Taylor coefficients in f_ - // (have to reconstruct them every time) - size_t c = 0; - size_t r = 0; - f_.capacity_order(c, r); - return ok; - } - // ------------------------------------------------------------------------ - /*! - Link from user_atomic to forward sparse Jacobian pack - - \copydetails atomic_base::for_sparse_jac - */ - virtual bool for_sparse_jac( - size_t q , - const vectorBool& r , - vectorBool& s , - const vector& x ) - { return for_sparse_jac< vectorBool >(q, r, s, x); - } - /*! - Link from user_atomic to forward sparse Jacobian bool - - \copydetails atomic_base::for_sparse_jac - */ - virtual bool for_sparse_jac( - size_t q , - const vector& r , - vector& s , - const vector& x ) - { return for_sparse_jac< vector >(q, r, s, x); - } - /*! - Link from user_atomic to forward sparse Jacobian sets - - \copydetails atomic_base::for_sparse_jac - */ - virtual bool for_sparse_jac( - size_t q , - const vector< std::set >& r , - vector< std::set >& s , - const vector& x ) - { // during user sparsity calculations - size_t m = f_.Range(); - size_t n = f_.Domain(); - if( jac_sparse_bool_.size() != 0 ) - jac_sparse_bool_.clear(); - if( jac_sparse_set_.n_set() == 0 ) - set_jac_sparse_set(); - CPPAD_ASSERT_UNKNOWN( jac_sparse_bool_.size() == 0 ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.n_set() == m ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.end() == n ); - CPPAD_ASSERT_UNKNOWN( r.size() == n ); - CPPAD_ASSERT_UNKNOWN( s.size() == m ); - - bool ok = true; - for(size_t i = 0; i < m; i++) - s[i].clear(); - - // sparsity for s = jac_sparse_set_ * r - for(size_t i = 0; i < m; i++) - { // compute row i of the return pattern - local::sparse_list::const_iterator set_itr(jac_sparse_set_, i); - size_t j = *set_itr; - while(j < n ) - { std::set::const_iterator itr_j; - const std::set& r_j( r[j] ); - for(itr_j = r_j.begin(); itr_j != r_j.end(); itr_j++) - { size_t k = *itr_j; - CPPAD_ASSERT_UNKNOWN( k < q ); - s[i].insert(k); - } - j = *(++set_itr); - } - } - - return ok; - } - // ------------------------------------------------------------------------ - /*! - Link from user_atomic to reverse sparse Jacobian pack - - \copydetails atomic_base::rev_sparse_jac - */ - virtual bool rev_sparse_jac( - size_t q , - const vectorBool& rt , - vectorBool& st , - const vector& x ) - { return rev_sparse_jac< vectorBool >(q, rt, st, x); - } - /*! - Link from user_atomic to reverse sparse Jacobian bool - - \copydetails atomic_base::rev_sparse_jac - */ - virtual bool rev_sparse_jac( - size_t q , - const vector& rt , - vector& st , - const vector& x ) - { return rev_sparse_jac< vector >(q, rt, st, x); - } - /*! - Link from user_atomic to reverse Jacobian sets - - \copydetails atomic_base::rev_sparse_jac - */ - virtual bool rev_sparse_jac( - size_t q , - const vector< std::set >& rt , - vector< std::set >& st , - const vector& x ) - { // during user sparsity calculations - size_t m = f_.Range(); - size_t n = f_.Domain(); - if( jac_sparse_bool_.size() != 0 ) - jac_sparse_bool_.clear(); - if( jac_sparse_set_.n_set() == 0 ) - set_jac_sparse_set(); - CPPAD_ASSERT_UNKNOWN( jac_sparse_bool_.size() == 0 ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.n_set() == m ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.end() == n ); - CPPAD_ASSERT_UNKNOWN( rt.size() == m ); - CPPAD_ASSERT_UNKNOWN( st.size() == n ); - // - bool ok = true; - // - for(size_t j = 0; j < n; j++) - st[j].clear(); - // - // sparsity for s = r * jac_sparse_set_ - // s^T = jac_sparse_set_^T * r^T - for(size_t i = 0; i < m; i++) - { // i is the row index in r^T - std::set::const_iterator itr_i; - const std::set& r_i( rt[i] ); - for(itr_i = r_i.begin(); itr_i != r_i.end(); itr_i++) - { // k is the column index in r^T - size_t k = *itr_i; - CPPAD_ASSERT_UNKNOWN( k < q ); - // - // i is column index in jac_sparse_set^T - local::sparse_list::const_iterator set_itr(jac_sparse_set_, i); - size_t j = *set_itr; - while( j < n ) - { // j is row index in jac_sparse_set^T - st[j].insert(k); - j = *(++set_itr); - } - } - } - - return ok; - } - // ------------------------------------------------------------------------ - /*! - Link from user_atomic to reverse sparse Hessian pack - - \copydetails atomic_base::rev_sparse_hes - */ - virtual bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const vectorBool& r , - const vectorBool& u , - vectorBool& v , - const vector& x ) - { return rev_sparse_hes< vectorBool >(vx, s, t, q, r, u, v, x); - } - /*! - Link from user_atomic to reverse sparse Hessian bool - - \copydetails atomic_base::rev_sparse_hes - */ - virtual bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const vector& r , - const vector& u , - vector& v , - const vector& x ) - { return rev_sparse_hes< vector >(vx, s, t, q, r, u, v, x); - } - /*! - Link from user_atomic to reverse sparse Hessian sets - - \copydetails atomic_base::rev_sparse_hes - */ - virtual bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const vector< std::set >& r , - const vector< std::set >& u , - vector< std::set >& v , - const vector& x ) - { size_t n = f_.Domain(); -# ifndef NDEBUG - size_t m = f_.Range(); -# endif - CPPAD_ASSERT_UNKNOWN( vx.size() == n ); - CPPAD_ASSERT_UNKNOWN( s.size() == m ); - CPPAD_ASSERT_UNKNOWN( t.size() == n ); - CPPAD_ASSERT_UNKNOWN( r.size() == n ); - CPPAD_ASSERT_UNKNOWN( u.size() == m ); - CPPAD_ASSERT_UNKNOWN( v.size() == n ); - // - bool ok = true; - - // make sure hes_sparse_set_ has been set - if( hes_sparse_bool_.size() != 0 ) - hes_sparse_bool_.clear(); - if( hes_sparse_set_.n_set() == 0 ) - set_hes_sparse_set(); - CPPAD_ASSERT_UNKNOWN( hes_sparse_bool_.size() == 0 ); - CPPAD_ASSERT_UNKNOWN( hes_sparse_set_.n_set() == n ); - CPPAD_ASSERT_UNKNOWN( hes_sparse_set_.end() == n ); - - // compute sparsity pattern for T(x) = S(x) * f'(x) - t = f_.RevSparseJac(1, s); -# ifndef NDEBUG - for(size_t j = 0; j < n; j++) - CPPAD_ASSERT_UNKNOWN( vx[j] || ! t[j] ) -# endif - - // V(x) = f'(x)^T * g''(y) * f'(x) * R + g'(y) * f''(x) * R - // U(x) = g''(y) * f'(x) * R - // S(x) = g'(y) - - // compute sparsity pattern for A(x) = f'(x)^T * U(x) - // 2DO: change a to use INTERNAL_SPARSE_SET - bool transpose = true; - vector< std::set > a(n); - a = f_.RevSparseJac(q, u, transpose); - - // Need sparsity pattern for H(x) = (S(x) * f(x))''(x) * R, - // but use less efficient sparsity for f(x)''(x) * R so that - // hes_sparse_set_ can be used every time this is needed. - for(size_t i = 0; i < n; i++) - { v[i].clear(); - local::sparse_list::const_iterator set_itr(hes_sparse_set_, i); - size_t j = *set_itr; - while( j < n ) - { std::set::const_iterator itr_j; - const std::set& r_j( r[j] ); - for(itr_j = r_j.begin(); itr_j != r_j.end(); itr_j++) - { size_t k = *itr_j; - v[i].insert(k); - } - j = *(++set_itr); - } - } - // compute sparsity pattern for V(x) = A(x) + H(x) - std::set::const_iterator itr; - for(size_t i = 0; i < n; i++) - { for(itr = a[i].begin(); itr != a[i].end(); itr++) - { size_t j = *itr; - CPPAD_ASSERT_UNKNOWN( j < q ); - v[i].insert(j); - } - } - - return ok; - } -}; - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/compare.hpp b/ct_core/include/ct/external/cppad/core/compare.hpp deleted file mode 100644 index 2fa6c817a..000000000 --- a/ct_core/include/ct/external/cppad/core/compare.hpp +++ /dev/null @@ -1,416 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_COMPARE_HPP -# define CPPAD_CORE_COMPARE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin Compare$$ -$spell - cos - Op - bool - const -$$ - - - -$section AD Binary Comparison Operators$$ -$mindex compare < <= > >= == !=$$ - - -$head Syntax$$ - -$icode%b% = %x% %Op% %y%$$ - - -$head Purpose$$ -Compares two operands where one of the operands is an -$codei%AD<%Base%>%$$ object. -The comparison has the same interpretation as for -the $icode Base$$ type. - - -$head Op$$ -The operator $icode Op$$ is one of the following: -$table -$bold Op$$ $pre $$ $cnext $bold Meaning$$ $rnext -$code <$$ $cnext is $icode x$$ less than $icode y$$ $rnext -$code <=$$ $cnext is $icode x$$ less than or equal $icode y$$ $rnext -$code >$$ $cnext is $icode x$$ greater than $icode y$$ $rnext -$code >=$$ $cnext is $icode x$$ greater than or equal $icode y$$ $rnext -$code ==$$ $cnext is $icode x$$ equal to $icode y$$ $rnext -$code !=$$ $cnext is $icode x$$ not equal to $icode y$$ -$tend - -$head x$$ -The operand $icode x$$ has prototype -$codei% - const %Type% &%x% -%$$ -where $icode Type$$ is $codei%AD<%Base%>%$$, $icode Base$$, or $code int$$. - -$head y$$ -The operand $icode y$$ has prototype -$codei% - const %Type% &%y% -%$$ -where $icode Type$$ is $codei%AD<%Base%>%$$, $icode Base$$, or $code int$$. - -$head b$$ -The result $icode b$$ has type -$codei% - bool %b% -%$$ - -$head Operation Sequence$$ -The result of this operation is a $code bool$$ value -(not an $cref/AD of Base/glossary/AD of Base/$$ object). -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. -$pre - -$$ -For example, suppose -$icode x$$ and $icode y$$ are $codei%AD<%Base%>%$$ objects, -the tape corresponding to $codei%AD<%Base%>%$$ is recording, -$icode b$$ is true, -and the subsequent code is -$codei% - if( %b% ) - %y% = cos(%x%); - else %y% = sin(%x%); -%$$ -only the assignment $icode%y% = cos(%x%)%$$ is recorded on the tape -(if $icode x$$ is a $cref/parameter/glossary/Parameter/$$, -nothing is recorded). -The $cref CompareChange$$ function can yield -some information about changes in comparison operation results. -You can use $cref CondExp$$ to obtain comparison operations -that depends on the -$cref/independent variable/glossary/Tape/Independent Variable/$$ -values with out re-taping the AD sequence of operations. - -$head Assumptions$$ -If one of the $icode Op$$ operators listed above -is used with an $codei%AD<%Base%>%$$ object, -it is assumed that the same operator is supported by the base type -$icode Base$$. - -$head Example$$ -$children% - example/compare.cpp -%$$ -The file -$cref compare.cpp$$ -contains an example and test of these operations. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ -// BEGIN CppAD namespace -namespace CppAD { - -// -------------------------------- < -------------------------- -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool operator < (const AD &left , const AD &right) -{ bool result = (left.value_ < right.value_); - bool var_left = Variable(left); - bool var_right = Variable(right); - - local::ADTape *tape = CPPAD_NULL; - if( var_left ) - { tape = left.tape_this(); - if( var_right ) - { if( result ) - { tape->Rec_.PutOp(local::LtvvOp); - tape->Rec_.PutArg(left.taddr_, right.taddr_); - } - else - { tape->Rec_.PutOp(local::LevvOp); - tape->Rec_.PutArg(right.taddr_, left.taddr_); - } - } - else - { addr_t arg1 = tape->Rec_.PutPar(right.value_); - if( result ) - { tape->Rec_.PutOp(local::LtvpOp); - tape->Rec_.PutArg(left.taddr_, arg1); - } - else - { tape->Rec_.PutOp(local::LepvOp); - tape->Rec_.PutArg(arg1, left.taddr_); - } - } - } - else if ( var_right ) - { tape = right.tape_this(); - addr_t arg0 = tape->Rec_.PutPar(left.value_); - if( result ) - { tape->Rec_.PutOp(local::LtpvOp); - tape->Rec_.PutArg(arg0, right.taddr_); - } - else - { tape->Rec_.PutOp(local::LevpOp); - tape->Rec_.PutArg(right.taddr_, arg0); - } - } - - return result; -} -// convert other cases into the case above -CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(<) - -// -------------------------------- <= ------------------------- -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool operator <= (const AD &left , const AD &right) -{ bool result = (left.value_ <= right.value_); - bool var_left = Variable(left); - bool var_right = Variable(right); - - local::ADTape *tape = CPPAD_NULL; - if( var_left ) - { tape = left.tape_this(); - if( var_right ) - { if( result ) - { tape->Rec_.PutOp(local::LevvOp); - tape->Rec_.PutArg(left.taddr_, right.taddr_); - } - else - { tape->Rec_.PutOp(local::LtvvOp); - tape->Rec_.PutArg(right.taddr_, left.taddr_); - } - } - else - { addr_t arg1 = tape->Rec_.PutPar(right.value_); - if( result ) - { tape->Rec_.PutOp(local::LevpOp); - tape->Rec_.PutArg(left.taddr_, arg1); - } - else - { tape->Rec_.PutOp(local::LtpvOp); - tape->Rec_.PutArg(arg1, left.taddr_); - } - } - } - else if ( var_right ) - { tape = right.tape_this(); - addr_t arg0 = tape->Rec_.PutPar(left.value_); - if( result ) - { tape->Rec_.PutOp(local::LepvOp); - tape->Rec_.PutArg(arg0, right.taddr_); - } - else - { tape->Rec_.PutOp(local::LtvpOp); - tape->Rec_.PutArg(right.taddr_, arg0); - } - } - - return result; -} -// convert other cases into the case above -CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(<=) - -// -------------------------------- > -------------------------- -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool operator > (const AD &left , const AD &right) -{ bool result = (left.value_ > right.value_); - bool var_left = Variable(left); - bool var_right = Variable(right); - - local::ADTape *tape = CPPAD_NULL; - if( var_left ) - { tape = left.tape_this(); - if( var_right ) - { if( result ) - { tape->Rec_.PutOp(local::LtvvOp); - tape->Rec_.PutArg(right.taddr_, left.taddr_); - } - else - { tape->Rec_.PutOp(local::LevvOp); - tape->Rec_.PutArg(left.taddr_, right.taddr_); - } - } - else - { addr_t arg1 = tape->Rec_.PutPar(right.value_); - if( result ) - { tape->Rec_.PutOp(local::LtpvOp); - tape->Rec_.PutArg(arg1, left.taddr_); - } - else - { tape->Rec_.PutOp(local::LevpOp); - tape->Rec_.PutArg(left.taddr_, arg1); - } - } - } - else if ( var_right ) - { tape = right.tape_this(); - addr_t arg0 = tape->Rec_.PutPar(left.value_); - if( result ) - { tape->Rec_.PutOp(local::LtvpOp); - tape->Rec_.PutArg(right.taddr_, arg0); - } - else - { tape->Rec_.PutOp(local::LepvOp); - tape->Rec_.PutArg(arg0, right.taddr_); - } - } - - return result; -} -// convert other cases into the case above -CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(>) - -// -------------------------------- >= ------------------------- -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool operator >= (const AD &left , const AD &right) -{ bool result = (left.value_ >= right.value_); - bool var_left = Variable(left); - bool var_right = Variable(right); - - local::ADTape *tape = CPPAD_NULL; - if( var_left ) - { tape = left.tape_this(); - if( var_right ) - { if( result ) - { tape->Rec_.PutOp(local::LevvOp); - tape->Rec_.PutArg(right.taddr_, left.taddr_); - } - else - { tape->Rec_.PutOp(local::LtvvOp); - tape->Rec_.PutArg(left.taddr_, right.taddr_); - } - } - else - { addr_t arg1 = tape->Rec_.PutPar(right.value_); - if( result ) - { tape->Rec_.PutOp(local::LepvOp); - tape->Rec_.PutArg(arg1, left.taddr_); - } - else - { tape->Rec_.PutOp(local::LtvpOp); - tape->Rec_.PutArg(left.taddr_, arg1); - } - } - } - else if ( var_right ) - { tape = right.tape_this(); - addr_t arg0 = tape->Rec_.PutPar(left.value_); - if( result ) - { tape->Rec_.PutOp(local::LevpOp); - tape->Rec_.PutArg(right.taddr_, arg0); - } - else - { tape->Rec_.PutOp(local::LtpvOp); - tape->Rec_.PutArg(arg0, right.taddr_); - } - } - - return result; -} -// convert other cases into the case above -CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(>=) - -// -------------------------------- == ------------------------- -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool operator == (const AD &left , const AD &right) -{ bool result = (left.value_ == right.value_); - bool var_left = Variable(left); - bool var_right = Variable(right); - - local::ADTape *tape = CPPAD_NULL; - if( var_left ) - { tape = left.tape_this(); - if( var_right ) - { tape->Rec_.PutArg(left.taddr_, right.taddr_); - if( result ) - tape->Rec_.PutOp(local::EqvvOp); - else - tape->Rec_.PutOp(local::NevvOp); - } - else - { addr_t arg1 = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(arg1, left.taddr_); - if( result ) - tape->Rec_.PutOp(local::EqpvOp); - else - tape->Rec_.PutOp(local::NepvOp); - } - } - else if ( var_right ) - { tape = right.tape_this(); - addr_t arg0 = tape->Rec_.PutPar(left.value_); - tape->Rec_.PutArg(arg0, right.taddr_); - if( result ) - tape->Rec_.PutOp(local::EqpvOp); - else - tape->Rec_.PutOp(local::NepvOp); - } - - return result; -} -// convert other cases into the case above -CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(==) - -// -------------------------------- != ------------------------- -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool operator != (const AD &left , const AD &right) -{ bool result = (left.value_ != right.value_); - bool var_left = Variable(left); - bool var_right = Variable(right); - - local::ADTape *tape = CPPAD_NULL; - if( var_left ) - { tape = left.tape_this(); - if( var_right ) - { tape->Rec_.PutArg(left.taddr_, right.taddr_); - if( result ) - tape->Rec_.PutOp(local::NevvOp); - else - tape->Rec_.PutOp(local::EqvvOp); - } - else - { addr_t arg1 = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(arg1, left.taddr_); - if( result ) - tape->Rec_.PutOp(local::NepvOp); - else - tape->Rec_.PutOp(local::EqpvOp); - } - } - else if ( var_right ) - { tape = right.tape_this(); - addr_t arg0 = tape->Rec_.PutPar(left.value_); - tape->Rec_.PutArg(arg0, right.taddr_); - if( result ) - tape->Rec_.PutOp(local::NepvOp); - else - tape->Rec_.PutOp(local::EqpvOp); - } - - return result; -} -// convert other cases into the case above -CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(!=) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/compound_assign.hpp b/ct_core/include/ct/external/cppad/core/compound_assign.hpp deleted file mode 100644 index 549fce725..000000000 --- a/ct_core/include/ct/external/cppad/core/compound_assign.hpp +++ /dev/null @@ -1,142 +0,0 @@ -# ifndef CPPAD_CORE_COMPOUND_ASSIGN_HPP -# define CPPAD_CORE_COMPOUND_ASSIGN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-17 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin compound_assign$$ -$spell - Op - VecAD - const -$$ - -$section AD Compound Assignment Operators$$ -$mindex + add plus - subtract minus * multiply times / divide multiple$$ - - - - - - -$head Syntax$$ -$icode%x% %Op% %y%$$ - -$head Purpose$$ -Performs compound assignment operations -where either $icode x$$ has type -$codei%AD<%Base%>%$$. - -$head Op$$ -The operator $icode Op$$ is one of the following -$table -$bold Op$$ $cnext $bold Meaning$$ $rnext -$code +=$$ $cnext $icode x$$ is assigned $icode x$$ plus $icode y$$ $rnext -$code -=$$ $cnext $icode x$$ is assigned $icode x$$ minus $icode y$$ $rnext -$code *=$$ $cnext $icode x$$ is assigned $icode x$$ times $icode y$$ $rnext -$code /=$$ $cnext $icode x$$ is assigned $icode x$$ divided by $icode y$$ -$tend - -$head Base$$ -The type $icode Base$$ is determined by the operand $icode x$$. - -$head x$$ -The operand $icode x$$ has the following prototype -$codei% - AD<%Base%> &%x% -%$$ - -$head y$$ -The operand $icode y$$ has the following prototype -$codei% - const %Type% &%y% -%$$ -where $icode Type$$ is -$codei%VecAD<%Base%>::reference%$$, -$codei%AD<%Base%>%$$, -$icode Base$$, or -$code double$$. - -$head Result$$ -The result of this assignment -can be used as a reference to $icode x$$. -For example, if $icode z$$ has the following type -$codei% - AD<%Base%> %z% -%$$ -then the syntax -$codei% - %z% = %x% += %y% -%$$ -will compute $icode x$$ plus $icode y$$ -and then assign this value to both $icode x$$ and $icode z$$. - - -$head Operation Sequence$$ -This is an $cref/atomic/glossary/Operation/Atomic/$$ -$cref/AD of Base/glossary/AD of Base/$$ operation -and hence it is part of the current -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$children% - example/add_eq.cpp% - example/sub_eq.cpp% - example/mul_eq.cpp% - example/div_eq.cpp -%$$ - -$head Example$$ -The following files contain examples and tests of these functions. -Each test returns true if it succeeds and false otherwise. -$table -$rref AddEq.cpp$$ -$rref sub_eq.cpp$$ -$rref mul_eq.cpp$$ -$rref div_eq.cpp$$ -$tend - -$head Derivative$$ -If $latex f$$ and $latex g$$ are -$cref/Base functions/glossary/Base Function/$$ - -$subhead Addition$$ -$latex \[ - \D{[ f(x) + g(x) ]}{x} = \D{f(x)}{x} + \D{g(x)}{x} -\] $$ - -$subhead Subtraction$$ -$latex \[ - \D{[ f(x) - g(x) ]}{x} = \D{f(x)}{x} - \D{g(x)}{x} -\] $$ - -$subhead Multiplication$$ -$latex \[ - \D{[ f(x) * g(x) ]}{x} = g(x) * \D{f(x)}{x} + f(x) * \D{g(x)}{x} -\] $$ - -$subhead Division$$ -$latex \[ - \D{[ f(x) / g(x) ]}{x} = - [1/g(x)] * \D{f(x)}{x} - [f(x)/g(x)^2] * \D{g(x)}{x} -\] $$ - -$end ------------------------------------------------------------------------------ -*/ -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/core/cond_exp.hpp b/ct_core/include/ct/external/cppad/core/cond_exp.hpp deleted file mode 100644 index 9c4c3c281..000000000 --- a/ct_core/include/ct/external/cppad/core/cond_exp.hpp +++ /dev/null @@ -1,355 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_COND_EXP_HPP -# define CPPAD_CORE_COND_EXP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin CondExp$$ -$spell - Atan2 - CondExp - Taylor - std - Cpp - namespace - inline - const - abs - Rel - bool - Lt - Le - Eq - Ge - Gt -$$ - - -$section AD Conditional Expressions$$ -$mindex assign$$ - -$head Syntax$$ -$icode%result% = CondExp%Rel%(%left%, %right%, %if_true%, %if_false%)%$$ - - -$head Purpose$$ -Record, -as part of an AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$, -the conditional result -$codei% - if( %left% %Cop% %right% ) - %result% = %if_true% - else %result% = %if_false% -%$$ -The relational $icode Rel$$ and comparison operator $icode Cop$$ -above have the following correspondence: -$codei% - %Rel% Lt Le Eq Ge Gt - %Cop% < <= == >= > -%$$ -If $icode f$$ is the $cref ADFun$$ object corresponding to the -AD operation sequence, -the assignment choice for $icode result$$ -in an AD conditional expression is made each time -$cref/f.Forward/Forward/$$ is used to evaluate the zero order Taylor -coefficients with new values for the -$cref/independent variables/glossary/Tape/Independent Variable/$$. -This is in contrast to the $cref/AD comparison operators/Compare/$$ -which are boolean valued and not included in the AD operation sequence. - -$head Rel$$ -In the syntax above, the relation $icode Rel$$ represents one of the following -two characters: $code Lt$$, $code Le$$, $code Eq$$, $code Ge$$, $code Gt$$. -As in the table above, -$icode Rel$$ determines which comparison operator $icode Cop$$ is used -when comparing $icode left$$ and $icode right$$. - -$head Type$$ -These functions are defined in the CppAD namespace for arguments of -$icode Type$$ is $code float$$ , $code double$$, or any type of the form -$codei%AD<%Base%>%$$. -(Note that all four arguments must have the same type.) - -$head left$$ -The argument $icode left$$ has prototype -$codei% - const %Type%& %left% -%$$ -It specifies the value for the left side of the comparison operator. - -$head right$$ -The argument $icode right$$ has prototype -$codei% - const %Type%& %right% -%$$ -It specifies the value for the right side of the comparison operator. - -$head if_true$$ -The argument $icode if_true$$ has prototype -$codei% - const %Type%& %if_true% -%$$ -It specifies the return value if the result of the comparison is true. - -$head if_false$$ -The argument $icode if_false$$ has prototype -$codei% - const %Type%& %if_false% -%$$ -It specifies the return value if the result of the comparison is false. - -$head result$$ -The $icode result$$ has prototype -$codei% - %Type%& %if_false% -%$$ - -$head Optimize$$ -The $cref optimize$$ method will optimize conditional expressions -in the following way: -During $cref/zero order forward mode/forward_zero/$$, -once the value of the $icode left$$ and $icode right$$ have been determined, -it is known if the true or false case is required. -From this point on, values corresponding to the case that is not required -are not computed. -This optimization is done for the rest of zero order forward mode -as well as forward and reverse derivatives calculations. - -$head Deprecate 2005-08-07$$ -Previous versions of CppAD used -$codei% - CondExp(%flag%, %if_true%, %if_false%) -%$$ -for the same meaning as -$codei% - CondExpGt(%flag%, %Type%(0), %if_true%, %if_false%) -%$$ -Use of $code CondExp$$ is deprecated, but continues to be supported. - -$head Operation Sequence$$ -This is an AD of $icode Base$$ -$cref/atomic operation/glossary/Operation/Atomic/$$ -and hence is part of the current -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - - -$head Example$$ - -$head Test$$ -$children% - example/cond_exp.cpp -%$$ -The file -$cref cond_exp.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$head Atan2$$ -The following implementation of the -AD $cref atan2$$ function is a more complex -example of using conditional expressions: -$code -$srcfile%cppad/core/atan2.hpp%0%BEGIN CondExp%// END CondExp%$$ -$$ - - -$end -------------------------------------------------------------------------------- -*/ -// BEGIN CppAD namespace -namespace CppAD { - -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -AD CondExpOp( - enum CompareOp cop , - const AD &left , - const AD &right , - const AD &if_true , - const AD &if_false ) -{ - AD returnValue; - CPPAD_ASSERT_UNKNOWN( Parameter(returnValue) ); - - // check first case where do not need to tape - if( IdenticalPar(left) & IdenticalPar(right) ) - { switch( cop ) - { - case CompareLt: - if( left.value_ < right.value_ ) - returnValue = if_true; - else returnValue = if_false; - break; - - case CompareLe: - if( left.value_ <= right.value_ ) - returnValue = if_true; - else returnValue = if_false; - break; - - case CompareEq: - if( left.value_ == right.value_ ) - returnValue = if_true; - else returnValue = if_false; - break; - - case CompareGe: - if( left.value_ >= right.value_ ) - returnValue = if_true; - else returnValue = if_false; - break; - - case CompareGt: - if( left.value_ > right.value_ ) - returnValue = if_true; - else returnValue = if_false; - break; - - default: - CPPAD_ASSERT_UNKNOWN(0); - returnValue = if_true; - } - return returnValue; - } - - // must use CondExp incase Base is an AD type and recording - returnValue.value_ = CondExpOp(cop, - left.value_, right.value_, if_true.value_, if_false.value_); - - local::ADTape *tape = CPPAD_NULL; - if( Variable(left) ) - tape = left.tape_this(); - if( Variable(right) ) - tape = right.tape_this(); - if( Variable(if_true) ) - tape = if_true.tape_this(); - if( Variable(if_false) ) - tape = if_false.tape_this(); - - // add this operation to the tape - if( tape != CPPAD_NULL ) - tape->RecordCondExp(cop, - returnValue, left, right, if_true, if_false); - - return returnValue; -} - -// --- RecordCondExp(cop, returnValue, left, right, if_true, if_false) ----- - -/// All these operations are done in \c Rec_, so we should move this -/// routine to recorder. -template -void local::ADTape::RecordCondExp( - enum CompareOp cop , - AD &returnValue , - const AD &left , - const AD &right , - const AD &if_true , - const AD &if_false ) -{ size_t ind0, ind1, ind2, ind3, ind4, ind5; - size_t returnValue_taddr; - - // taddr_ of this variable - CPPAD_ASSERT_UNKNOWN( NumRes(CExpOp) == 1 ); - returnValue_taddr = Rec_.PutOp(CExpOp); - - // ind[0] = cop - ind0 = addr_t( cop ); - - // ind[1] = base 2 represenation of the value - // [Var(left), Var(right), Var(if_true), Var(if_false)] - ind1 = 0; - - // Make sure returnValue is in the list of variables and set its taddr - if( Parameter(returnValue) ) - returnValue.make_variable(id_, returnValue_taddr ); - else returnValue.taddr_ = returnValue_taddr; - - // ind[2] = left address - if( Parameter(left) ) - ind2 = Rec_.PutPar(left.value_); - else - { ind1 += 1; - ind2 = left.taddr_; - } - - // ind[3] = right address - if( Parameter(right) ) - ind3 = Rec_.PutPar(right.value_); - else - { ind1 += 2; - ind3 = right.taddr_; - } - - // ind[4] = if_true address - if( Parameter(if_true) ) - ind4 = Rec_.PutPar(if_true.value_); - else - { ind1 += 4; - ind4 = if_true.taddr_; - } - - // ind[5] = if_false address - if( Parameter(if_false) ) - ind5 = Rec_.PutPar(if_false.value_); - else - { ind1 += 8; - ind5 = if_false.taddr_; - } - - CPPAD_ASSERT_UNKNOWN( NumArg(CExpOp) == 6 ); - CPPAD_ASSERT_UNKNOWN( ind1 > 0 ); - Rec_.PutArg(ind0, ind1, ind2, ind3, ind4, ind5); - - // check that returnValue is a dependent variable - CPPAD_ASSERT_UNKNOWN( Variable(returnValue) ); -} - -// ------------ CondExpOp(left, right, if_true, if_false) ---------------- - -# define CPPAD_COND_EXP(Name) \ - template \ - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION \ - AD CondExp##Name( \ - const AD &left , \ - const AD &right , \ - const AD &if_true , \ - const AD &if_false ) \ - { \ - return CondExpOp(Compare##Name, \ - left, right, if_true, if_false); \ - } - -// AD -CPPAD_COND_EXP(Lt) -CPPAD_COND_EXP(Le) -CPPAD_COND_EXP(Eq) -CPPAD_COND_EXP(Ge) -CPPAD_COND_EXP(Gt) -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -AD CondExp( - const AD &flag , - const AD &if_true , - const AD &if_false ) -{ - return CondExpOp(CompareGt, flag, AD(0), if_true, if_false); -} - -# undef CPPAD_COND_EXP -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/convert.hpp b/ct_core/include/ct/external/cppad/core/convert.hpp deleted file mode 100644 index 388781152..000000000 --- a/ct_core/include/ct/external/cppad/core/convert.hpp +++ /dev/null @@ -1,52 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_CONVERT_HPP -# define CPPAD_CORE_CONVERT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Convert$$ -$spell -$$ - - -$section Conversion and I/O of AD Objects$$ -$mindex convert from$$ - -$children% - cppad/core/value.hpp% - cppad/core/integer.hpp% - cppad/core/ad_to_string.hpp% - cppad/core/ad_io.hpp% - cppad/core/print_for.hpp% - cppad/core/var2par.hpp -%$$ -$table -$rref Value$$ -$rref Integer$$ -$rref ad_output$$ -$rref PrintFor$$ -$rref Var2Par$$ -$tend - - -$end -*/ - -# include -# include -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/core/cppad_assert.hpp b/ct_core/include/ct/external/cppad/core/cppad_assert.hpp deleted file mode 100644 index 76ac9801b..000000000 --- a/ct_core/include/ct/external/cppad/core/cppad_assert.hpp +++ /dev/null @@ -1,205 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_CPPAD_ASSERT_HPP -# define CPPAD_CORE_CPPAD_ASSERT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/*! -\file cppad_assert.hpp -Define the CppAD error checking macros (all of which begin with CPPAD_ASSERT_) -*/ - -/* -------------------------------------------------------------------------------- -$begin cppad_assert$$ -$spell - CppAD - exp - const - bool -$$ - - -$section CppAD Assertions During Execution$$ -$mindex assert macro CPPAD_ASSERT_KNOWN CPPAD_ASSERT_UNKNOWN$$ - -$head Syntax$$ -$codei%CPPAD_ASSERT_KNOWN(%exp%, %msg%) -%$$ -$codei%CPPAD_ASSERT_UNKNOWN(%exp%)%$$ - - -$head Purpose$$ -These CppAD macros are used to detect and report errors. -They are documented here because they correspond to the C++ -source code that the error is reported at. - -$head NDEBUG$$ -If the preprocessor symbol -$cref/NDEBUG/Faq/Speed/NDEBUG/$$ is defined, -these macros do nothing; i.e., they are optimized out. - -$head Restriction$$ -The CppAD user should not uses these macros. -You can however write your own macros that do not begin with $code CPPAD$$ -and that call the $cref/CppAD error handler/ErrorHandler/$$. - -$head Known$$ -The $code CPPAD_ASSERT_KNOWN$$ macro is used to check for an error -with a known cause. -For example, many CppAD routines uses these macros -to make sure their arguments conform to their specifications. - -$head Unknown$$ -The $code CPPAD_ASSERT_UNKNOWN$$ macro is used to check that the -CppAD internal data structures conform as expected. -If this is not the case, CppAD does not know why the error has -occurred; for example, the user may have written past the end -of an allocated array. - -$head Exp$$ -The argument $icode exp$$ is a C++ source code expression -that results in a $code bool$$ value that should be true. -If it is false, an error has occurred. -This expression may be execute any number of times -(including zero times) so it must have not side effects. - -$head Msg$$ -The argument $icode msg$$ has prototype -$codei% - const char *%msg% -%$$ -and contains a $code '\0'$$ terminated character string. -This string is a description of the error -corresponding to $icode exp$$ being false. - -$head Error Handler$$ -These macros use the -$cref/CppAD error handler/ErrorHandler/$$ to report errors. -This error handler can be replaced by the user. - -$end ------------------------------------------------------------------------------- -*/ - -# include -# include -# include - -/*! -\def CPPAD_ASSERT_KNOWN(exp, msg) -Check that \a exp is true, if not print \a msg and terminate execution. - -The C++ expression \a exp is expected to be true. -If it is false, -the CppAD use has made an error that is described by \a msg. -If the preprocessor symbol \a NDEBUG is not defined, -and \a exp is false, -this macro will report the source code line number at -which this expected result occurred. -In addition, it will print the specified error message \a msg. -*/ -# ifdef NDEBUG -# define CPPAD_ASSERT_KNOWN(exp, msg) // do nothing -# else -# define CPPAD_ASSERT_KNOWN(exp, msg) \ -{ if( ! ( exp ) ) \ - CppAD::ErrorHandler::Call( \ - true , \ - __LINE__ , \ - __FILE__ , \ - #exp , \ - msg ); \ -} -# endif - -/*! -\def CPPAD_ASSERT_UNKNOWN(exp) -Check that \a exp is true, if not terminate execution. - -The C++ expression \a exp is expected to be true. -If it is false, -CppAD has detected an error but does not know the cause of the error. -If the preprocessor symbol \a NDEBUG is not defined, -and \a exp is false, -this macro will report the source code line number at -which this expected result occurred. -*/ -# ifdef NDEBUG -# define CPPAD_ASSERT_UNKNOWN(exp) // do nothing -# else -# define CPPAD_ASSERT_UNKNOWN(exp) \ -{ if( ! ( exp ) ) \ - CppAD::ErrorHandler::Call( \ - false , \ - __LINE__ , \ - __FILE__ , \ - #exp , \ - "" ); \ -} -# endif - -/*! -\def CPPAD_ASSERT_NARG_NRES(op, n_arg, n_res) -Check that operator \a op has the specified number of of arguments and results. - -If \a NDEBUG is not defined and either the number of arguments -or the number of results are not as expected, -execution is terminated and the source code line number is reported. -*/ -# define CPPAD_ASSERT_NARG_NRES(op, n_arg, n_res) \ - CPPAD_ASSERT_UNKNOWN( NumArg(op) == n_arg ) \ - CPPAD_ASSERT_UNKNOWN( NumRes(op) == n_res ) - -/*! -\def CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -Check that the first call to a routine is not during parallel execution mode. - -If \c NDEBUG is defined, this macro has no effect -(not even the definition of (\c assert_first_call). -Otherwise, the variable -\code - static bool assert_first_call -\endcode -is defined and if the first call is executed in parallel mode, -execution is terminated and the source code line number is reported. -*/ -# ifdef NDEBUG -# define CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# else -# define CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL \ - static bool assert_first_call = true; \ - if( assert_first_call ) \ - { CPPAD_ASSERT_KNOWN( \ - ! (CppAD::thread_alloc::in_parallel() ), \ - "In parallel mode and parallel_setup has not been called." \ - ); \ - assert_first_call = false; \ - } -# endif - -/*! -\def CPPAD_ASSERT_ARG_BEFORE_RESULT -Check that operator arguments come before result. - -If \c NDEBUG is defined, this macro has no effect, -otherwise it calls the function assert_arg_before_result. -*/ -# ifdef NDEBUG -# define CPPAD_ASSERT_ARG_BEFORE_RESULT(op, arg, result) -# else -# define CPPAD_ASSERT_ARG_BEFORE_RESULT(op, arg, result) \ - assert_arg_before_result(op, arg, result) - -# endif - -# endif diff --git a/ct_core/include/ct/external/cppad/core/define.hpp b/ct_core/include/ct/external/cppad/core/define.hpp deleted file mode 100644 index faba1c611..000000000 --- a/ct_core/include/ct/external/cppad/core/define.hpp +++ /dev/null @@ -1,325 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_DEFINE_HPP -# define CPPAD_CORE_DEFINE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/*! -\file define.hpp -Define processor symbols and macros that are used by CppAD. -*/ - -// ---------------------------------------------------------------------------- -/*! -\def CPPAD_OP_CODE_TYPE -Is the type used to store enum OpCode values. If not the same as OpCode, then -sizeof(CPPAD_OP_CODE_TYPE) <= sizeof( enum OpCode ) -to conserve memory. -This type must support \c std::numeric_limits, -the \c <= operator, -and conversion to \c size_t. -Make sure that the type chosen returns true for is_pod -in pod_vector.hpp. -*/ -# define CPPAD_OP_CODE_TYPE unsigned char - - -// ---------------------------------------------------------------------------- -/*! -\def CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -A version of the inline command that works with MC compiler. - -Microsoft Visual C++ version 9.0 generates a warning if a template -function is declared as a friend -(this was not a problem for version 7.0). -The warning identifier is -\verbatim - warning C4396 -\endverbatim -and it contains the text -\verbatim - the inline specifier cannot be used when a friend declaration refers - to a specialization of a function template -\endverbatim -This happens even if the function is not a specialization. -This macro is defined as empty for Microsoft compilers. -*/ -# ifdef _MSC_VER -# define CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -# else -# define CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION inline -# endif - -// ---------------------------------------------------------------------------- -/*! -\def CPPAD_LIB_EXPORT -Special macro for exporting windows DLL symbols; see -https://cmake.org/Wiki/BuildingWinDLL -*/ -# ifdef _MSC_VER -# ifdef cppad_lib_EXPORTS -# define CPPAD_LIB_EXPORT __declspec(dllexport) -# else -# define CPPAD_LIB_EXPORT __declspec(dllimport) -# endif // cppad_lib_EXPORTS -# else // _MSC_VER -# define CPPAD_LIB_EXPORT -# endif - - -// ============================================================================ -/*! -\def CPPAD_FOLD_ASSIGNMENT_OPERATOR(Op) -Declares automatic coercion for certain AD assignment operations. - -This macro assumes that the operator -\verbatim - left Op right -\endverbatim -is defined for the case where left and right have type AD. -It uses this case to define the cases where -left has type AD and right has type -VecAD_reference, -Base, or -double. -The argument right is const and call by reference. -This macro converts the operands to AD and then -uses the definition of the same operation for that case. -*/ - -# define CPPAD_FOLD_ASSIGNMENT_OPERATOR(Op) \ -/* ----------------------------------------------------------------*/ \ -template \ -inline AD& operator Op \ -(AD &left, double right) \ -{ return left Op AD(right); } \ - \ -template \ -inline AD& operator Op \ -(AD &left, const Base &right) \ -{ return left Op AD(right); } \ - \ -inline AD& operator Op \ -(AD &left, const double &right) \ -{ return left Op AD(right); } \ - \ -template \ -inline AD& operator Op \ -(AD &left, const VecAD_reference &right) \ -{ return left Op right.ADBase(); } - -// ===================================================================== -/*! -\def CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR(Op) -Declares automatic coercion for certain binary operations with AD result. - -This macro assumes that the operator -\verbatim - left Op right -\endverbatim -is defined for the case where left and right -and the result of the operation all -have type AD. -It uses this case to define the cases either left -or right has type VecAD_reference or AD -and the type of the other operand is one of the following: -VecAD_reference, AD, Base, double. -All of the arguments are const and call by reference. -This macro converts the operands to AD and then -uses the definition of the same operation for that case. -*/ -# define CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR(Op) \ -/* ----------------------------------------------------------------*/ \ -/* Operations with VecAD_reference and AD only*/ \ - \ -template \ -inline AD operator Op \ -(const AD &left, const VecAD_reference &right) \ -{ return left Op right.ADBase(); } \ - \ -template \ -inline AD operator Op \ -(const VecAD_reference &left, const VecAD_reference &right)\ -{ return left.ADBase() Op right.ADBase(); } \ - \ -template \ -inline AD operator Op \ - (const VecAD_reference &left, const AD &right) \ -{ return left.ADBase() Op right; } \ -/* ----------------------------------------------------------------*/ \ -/* Operations Base */ \ - \ -template \ -inline AD operator Op \ - (const Base &left, const AD &right) \ -{ return AD(left) Op right; } \ - \ -template \ -inline AD operator Op \ - (const Base &left, const VecAD_reference &right) \ -{ return AD(left) Op right.ADBase(); } \ - \ -template \ -inline AD operator Op \ - (const AD &left, const Base &right) \ -{ return left Op AD(right); } \ - \ -template \ -inline AD operator Op \ - (const VecAD_reference &left, const Base &right) \ -{ return left.ADBase() Op AD(right); } \ - \ -/* ----------------------------------------------------------------*/ \ -/* Operations double */ \ - \ -template \ -inline AD operator Op \ - (const double &left, const AD &right) \ -{ return AD(left) Op right; } \ - \ -template \ -inline AD operator Op \ - (const double &left, const VecAD_reference &right) \ -{ return AD(left) Op right.ADBase(); } \ - \ -template \ -inline AD operator Op \ - (const AD &left, const double &right) \ -{ return left Op AD(right); } \ - \ -template \ -inline AD operator Op \ - (const VecAD_reference &left, const double &right) \ -{ return left.ADBase() Op AD(right); } \ -/* ----------------------------------------------------------------*/ \ -/* Special case to avoid ambuigity when Base is double */ \ - \ -inline AD operator Op \ - (const double &left, const AD &right) \ -{ return AD(left) Op right; } \ - \ -inline AD operator Op \ - (const double &left, const VecAD_reference &right) \ -{ return AD(left) Op right.ADBase(); } \ - \ -inline AD operator Op \ - (const AD &left, const double &right) \ -{ return left Op AD(right); } \ - \ -inline AD operator Op \ - (const VecAD_reference &left, const double &right) \ -{ return left.ADBase() Op AD(right); } - -// ======================================================================= - -/*! -\def CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(Op) -Declares automatic coercion for certain binary operations with bool result. - -This macro assumes that the operator -\verbatim - left Op right -\endverbatim -is defined for the case where left and right -have type AD and the result has type bool. -It uses this case to define the cases either left -or right has type -VecAD_reference or AD -and the type of the other operand is one of the following: -VecAD_reference, AD, Base, double. -All of the arguments are const and call by reference. -This macro converts the operands to AD and then -uses the definition of the same operation for that case. -*/ -# define CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(Op) \ -/* ----------------------------------------------------------------*/ \ -/* Operations with VecAD_reference and AD only*/ \ - \ -template \ -inline bool operator Op \ -(const AD &left, const VecAD_reference &right) \ -{ return left Op right.ADBase(); } \ - \ -template \ -inline bool operator Op \ -(const VecAD_reference &left, const VecAD_reference &right)\ -{ return left.ADBase() Op right.ADBase(); } \ - \ -template \ -inline bool operator Op \ - (const VecAD_reference &left, const AD &right) \ -{ return left.ADBase() Op right; } \ -/* ----------------------------------------------------------------*/ \ -/* Operations Base */ \ - \ -template \ -inline bool operator Op \ - (const Base &left, const AD &right) \ -{ return AD(left) Op right; } \ - \ -template \ -inline bool operator Op \ - (const Base &left, const VecAD_reference &right) \ -{ return AD(left) Op right.ADBase(); } \ - \ -template \ -inline bool operator Op \ - (const AD &left, const Base &right) \ -{ return left Op AD(right); } \ - \ -template \ -inline bool operator Op \ - (const VecAD_reference &left, const Base &right) \ -{ return left.ADBase() Op AD(right); } \ - \ -/* ----------------------------------------------------------------*/ \ -/* Operations double */ \ - \ -template \ -inline bool operator Op \ - (const double &left, const AD &right) \ -{ return AD(left) Op right; } \ - \ -template \ -inline bool operator Op \ - (const double &left, const VecAD_reference &right) \ -{ return AD(left) Op right.ADBase(); } \ - \ -template \ -inline bool operator Op \ - (const AD &left, const double &right) \ -{ return left Op AD(right); } \ - \ -template \ -inline bool operator Op \ - (const VecAD_reference &left, const double &right) \ -{ return left.ADBase() Op AD(right); } \ -/* ----------------------------------------------------------------*/ \ -/* Special case to avoid ambuigity when Base is double */ \ - \ -inline bool operator Op \ - (const double &left, const AD &right) \ -{ return AD(left) Op right; } \ - \ -inline bool operator Op \ - (const double &left, const VecAD_reference &right) \ -{ return AD(left) Op right.ADBase(); } \ - \ -inline bool operator Op \ - (const AD &left, const double &right) \ -{ return left Op AD(right); } \ - \ -inline bool operator Op \ - (const VecAD_reference &left, const double &right) \ -{ return left.ADBase() Op AD(right); } - -# endif diff --git a/ct_core/include/ct/external/cppad/core/dependent.hpp b/ct_core/include/ct/external/cppad/core/dependent.hpp deleted file mode 100644 index a6f6775b1..000000000 --- a/ct_core/include/ct/external/cppad/core/dependent.hpp +++ /dev/null @@ -1,332 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_DEPENDENT_HPP -# define CPPAD_CORE_DEPENDENT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin Dependent$$ -$spell - alloc - num - taylor_ - ADvector - const -$$ - -$spell -$$ - -$section Stop Recording and Store Operation Sequence$$ -$mindex ADFun tape Dependent$$ - - -$head Syntax$$ -$icode%f%.Dependent(%x%, %y%)%$$ - -$head Purpose$$ -Stop recording and the AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$ -that started with the call -$codei% - Independent(%x%) -%$$ -and store the operation sequence in $icode f$$. -The operation sequence defines an -$cref/AD function/glossary/AD Function/$$ -$latex \[ - F : B^n \rightarrow B^m -\] $$ -where $latex B$$ is the space corresponding to objects of type $icode Base$$. -The value $latex n$$ is the dimension of the -$cref/domain/seq_property/Domain/$$ space for the operation sequence. -The value $latex m$$ is the dimension of the -$cref/range/seq_property/Range/$$ space for the operation sequence -(which is determined by the size of $icode y$$). - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -The AD of $icode Base$$ operation sequence is stored in $icode f$$; i.e., -it becomes the operation sequence corresponding to $icode f$$. -If a previous operation sequence was stored in $icode f$$, -it is deleted. - -$head x$$ -The argument $icode x$$ -must be the vector argument in a previous call to -$cref Independent$$. -Neither its size, or any of its values, are allowed to change -between calling -$codei% - Independent(%x%) -%$$ -and -$codei% - %f%.Dependent(%x%, %y%) -%$$. - -$head y$$ -The vector $icode y$$ has prototype -$codei% - const %ADvector% &%y% -%$$ -(see $cref/ADvector/FunConstruct/$$ below). -The length of $icode y$$ must be greater than zero -and is the dimension of the range space for $icode f$$. - -$head ADvector$$ -The type $icode ADvector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$codei%AD<%Base%>%$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Taping$$ -The tape, -that was created when $codei%Independent(%x%)%$$ was called, -will stop recording. -The AD operation sequence will be transferred from -the tape to the object $icode f$$ and the tape will then be deleted. - -$head Forward$$ -No $cref Forward$$ calculation is preformed during this operation. -Thus, directly after this operation, -$codei% - %f%.size_order() -%$$ -is zero (see $cref size_order$$). - -$head Parallel Mode$$ -The call to $code Independent$$, -and the corresponding call to -$codei% - ADFun<%Base%> %f%( %x%, %y%) -%$$ -or -$codei% - %f%.Dependent( %x%, %y%) -%$$ -or $cref abort_recording$$, -must be preformed by the same thread; i.e., -$cref/thread_alloc::thread_num/ta_thread_num/$$ must be the same. - -$head Example$$ -The file -$cref fun_check.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ----------------------------------------------------------------------------- -*/ - - -// BEGIN CppAD namespace -namespace CppAD { - -/*! -\file dependent.hpp -Different versions of Dependent function. -*/ - -/*! -Determine the \c tape corresponding to this exeuction thread and then use -Dependent(tape, y) to store this tapes recording in a function. - -\param y [in] -The dependent variable vector for the corresponding function. -*/ -template -template -void ADFun::Dependent(const ADvector &y) -{ local::ADTape* tape = AD::tape_ptr(); - CPPAD_ASSERT_KNOWN( - tape != CPPAD_NULL, - "Can't store current operation sequence in this ADFun object" - "\nbecause there is no active tape (for this thread)." - ); - - // code above just determines the tape and checks for errors - Dependent(tape, y); -} - - -/*! -Determine the \c tape corresponding to this exeuction thread and then use -Dependent(tape, y) to store this tapes recording in a function. - -\param x [in] -The independent variable vector for this tape. This informaiton is -also stored in the tape so a check is done to make sure it is correct -(if NDEBUG is not defined). - -\param y [in] -The dependent variable vector for the corresponding function. -*/ -template -template -void ADFun::Dependent(const ADvector &x, const ADvector &y) -{ - CPPAD_ASSERT_KNOWN( - x.size() > 0, - "Dependent: independent variable vector has size zero." - ); - CPPAD_ASSERT_KNOWN( - Variable(x[0]), - "Dependent: independent variable vector has been changed." - ); - local::ADTape *tape = AD::tape_ptr(x[0].tape_id_); - CPPAD_ASSERT_KNOWN( - tape->size_independent_ == size_t( x.size() ), - "Dependent: independent variable vector has been changed." - ); -# ifndef NDEBUG - size_t i, j; - for(j = 0; j < size_t(x.size()); j++) - { CPPAD_ASSERT_KNOWN( - size_t(x[j].taddr_) == (j+1), - "ADFun: independent variable vector has been changed." - ); - CPPAD_ASSERT_KNOWN( - x[j].tape_id_ == x[0].tape_id_, - "ADFun: independent variable vector has been changed." - ); - } - for(i = 0; i < size_t(y.size()); i++) - { CPPAD_ASSERT_KNOWN( - CppAD::Parameter( y[i] ) | (y[i].tape_id_ == x[0].tape_id_) , - "ADFun: dependent vector contains a variable for" - "\na different tape (thread) than the independent variables." - ); - } -# endif - - // code above just determines the tape and checks for errors - Dependent(tape, y); -} - -/*! -Replace the floationg point operations sequence for this function object. - -\param tape -is a tape that contains the new floating point operation sequence -for this function. -After this operation, all memory allocated for this tape is deleted. - -\param y -The dependent variable vector for the function being stored in this object. - -\par -All of the private member data in ad_fun.hpp is set to correspond to the -new tape except for check_for_nan_. -*/ - -template -template -void ADFun::Dependent(local::ADTape *tape, const ADvector &y) -{ - size_t m = y.size(); - size_t n = tape->size_independent_; - size_t i, j; - size_t y_taddr; - - // check ADvector is Simple Vector class with AD elements - CheckSimpleVector< AD, ADvector>(); - - CPPAD_ASSERT_KNOWN( - y.size() > 0, - "ADFun operation sequence dependent variable size is zero size" - ); - // --------------------------------------------------------------------- - // Begin setting ad_fun.hpp private member data - // --------------------------------------------------------------------- - // dep_parameter_, dep_taddr_ - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::ParOp) == 1 ); - dep_parameter_.resize(m); - dep_taddr_.resize(m); - for(i = 0; i < m; i++) - { dep_parameter_[i] = CppAD::Parameter(y[i]); - if( dep_parameter_[i] ) - { // make a tape copy of dependent variables that are parameters, - y_taddr = tape->RecordParOp( y[i].value_ ); - } - else y_taddr = y[i].taddr_; - - CPPAD_ASSERT_UNKNOWN( y_taddr > 0 ); - dep_taddr_[i] = y_taddr; - } - - // put an EndOp at the end of the tape - tape->Rec_.PutOp(local::EndOp); - - // some size_t values in ad_fun.hpp - has_been_optimized_ = false; - compare_change_count_ = 1; - compare_change_number_ = 0; - compare_change_op_index_ = 0; - num_order_taylor_ = 0; - num_direction_taylor_ = 0; - cap_order_taylor_ = 0; - - // num_var_tape_ - // Now that all the variables are in the tape, we can set this value. - num_var_tape_ = tape->Rec_.num_var_rec(); - - // taylor_ - taylor_.erase(); - - // cskip_op_ - cskip_op_.erase(); - cskip_op_.extend( tape->Rec_.num_op_rec() ); - - // load_op_ - load_op_.erase(); - load_op_.extend( tape->Rec_.num_load_op_rec() ); - - // play_ - // Now that each dependent variable has a place in the tape, - // and there is a EndOp at the end of the tape, we can transfer the - // recording to the player and and erase the tape. - play_.get(tape->Rec_); - - // ind_taddr_ - // Note that play_ has been set, we can use it to check operators - ind_taddr_.resize(n); - CPPAD_ASSERT_UNKNOWN( n < num_var_tape_); - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( play_.GetOp(j+1) == local::InvOp ); - ind_taddr_[j] = j+1; - } - - // for_jac_sparse_pack_, for_jac_sparse_set_ - for_jac_sparse_pack_.resize(0, 0); - for_jac_sparse_set_.resize(0,0); - // --------------------------------------------------------------------- - // End set ad_fun.hpp private member data - // --------------------------------------------------------------------- - - // now we can delete the tape - AD::tape_manage(tape_manage_delete); - - // total number of varables in this recording - CPPAD_ASSERT_UNKNOWN( num_var_tape_ == play_.num_var_rec() ); - - // used to determine if there is an operation sequence in *this - CPPAD_ASSERT_UNKNOWN( num_var_tape_ > 0 ); - -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/discrete.hpp b/ct_core/include/ct/external/cppad/core/discrete.hpp deleted file mode 100644 index 9f976135e..000000000 --- a/ct_core/include/ct/external/cppad/core/discrete.hpp +++ /dev/null @@ -1,303 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_DISCRETE_HPP -# define CPPAD_CORE_DISCRETE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Discrete$$ -$spell - retaping - namespace - std - Eq - Cpp - const - inline - Geq -$$ - -$section Discrete AD Functions$$ -$mindex CPPAD_DISCRETE_FUNCTION$$ - - -$head Syntax$$ -$codei%CPPAD_DISCRETE_FUNCTION(%Base%, %name%) -%$$ -$icode%y% = %name%(%x%) -%$$ -$icode%ay% = %name%(%ax%) -%$$ - - -$head Purpose$$ -Record the evaluation of a discrete function as part -of an $codei%AD<%Base%>%$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. -The value of a discrete function can depend on the -$cref/independent variables/glossary/Tape/Independent Variable/$$, -but its derivative is identically zero. -For example, suppose that the integer part of -a $cref/variable/glossary/Variable/$$ $icode x$$ is the -index into an array of values. - -$head Base$$ -This is the -$cref/base type/base_require/$$ -corresponding to the operations sequence; -i.e., use of the $icode name$$ with arguments of type -$codei%AD<%Base%>%$$ can be recorded in an operation sequence. - -$head name$$ -This is the name of the function (as it is used in the source code). -The user must provide a version of $icode name$$ -where the argument has type $icode Base$$. -CppAD uses this to create a version of $icode name$$ -where the argument has type $codei%AD<%Base%>%$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Base%& %x% -%$$ -It is the value at which the user provided version of $icode name$$ -is to be evaluated. - -$head y$$ -The result $icode y$$ has prototype -$codei% - %Base% %y% -%$$ -It is the return value for the user provided version of $icode name$$. - -$head ax$$ -The argument $icode ax$$ has prototype -$codei% - const AD<%Base%>& %ax% -%$$ -It is the value at which the CppAD provided version of $icode name$$ -is to be evaluated. - -$head ay$$ -The result $icode ay$$ has prototype -$codei% - AD<%Base%> %ay% -%$$ -It is the return value for the CppAD provided version of $icode name$$. - - -$head Create AD Version$$ -The preprocessor macro invocation -$codei% - CPPAD_DISCRETE_FUNCTION(%Base%, %name%) -%$$ -defines the $codei%AD<%Base%>%$$ version of $icode name$$. -This can be with in a namespace (not the $code CppAD$$ namespace) -but must be outside of any routine. - -$head Operation Sequence$$ -This is an AD of $icode Base$$ -$cref/atomic operation/glossary/Operation/Atomic/$$ -and hence is part of the current -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Derivatives$$ -During a zero order $cref Forward$$ operation, -an $cref ADFun$$ object will compute the value of $icode name$$ -using the user provided $icode Base$$ version of this routine. -All the derivatives of $icode name$$ will be evaluated as zero. - -$head Parallel Mode$$ -The first call to -$codei% - %ay% = %name%(%ax%) -%$$ -must not be in $cref/parallel/ta_in_parallel/$$ execution mode. - - -$head Example$$ -$children% - example/tape_index.cpp% - example/interp_onetape.cpp% - example/interp_retape.cpp -%$$ -The file -$cref tape_index.cpp$$ -contains an example and test that uses a discrete function -to vary an array index during $cref Forward$$ mode calculations. -The file -$cref interp_onetape.cpp$$ -contains an example and test that uses discrete -functions to avoid retaping a calculation that requires interpolation. -(The file -$cref interp_retape.cpp$$ -shows how interpolation can be done with retaping.) - -$head CppADCreateDiscrete Deprecated 2007-07-28$$ -The preprocessor symbol $code CppADCreateDiscrete$$ -is defined to be the same as $code CPPAD_DISCRETE_FUNCTION$$ -but its use is deprecated. - -$end ------------------------------------------------------------------------------- -*/ -# include -# include - -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file discrete.hpp -user define discrete functions -*/ - -/*! -\def CPPAD_DISCRETE_FUNCTION(Base, name) -Defines the function name(ax, ay) -where \c ax and \c ay are vectors with AD elements. - -\par Base -is the base type for the discrete function. - -\par name -is the name of the user defined function that corresponding to this operation. -*/ - -# define CPPAD_DISCRETE_FUNCTION(Base, name) \ -inline CppAD::AD name (const CppAD::AD& ax) \ -{ \ - static CppAD::discrete fun(#name, name); \ - \ - return fun.ad(ax); \ -} -# define CppADCreateDiscrete CPPAD_DISCRETE_FUNCTION - - -/* -Class that acutally implemnets the ay = name(ax) call. - -A new discrete function is generated for ech time the user invokes -the CPPAD_DISCRETE_FUNCTION macro; see static object in that macro. -*/ -template -class discrete { - /// parallel_ad needs to call List to initialize static - template - friend void parallel_ad(void); - - /// type for the user routine that computes function values - typedef Base (*F) (const Base& x); -private: - /// name of this user defined function - const std::string name_; - /// user's implementation of the function for Base operations - const F f_; - /// index of this objec in the vector of all objects for this class - const size_t index_; - - /*! - List of all objects in this class. - - If we use CppAD::vector for this vector, it will appear that - there is a memory leak because this list is not distroyed before - thread_alloc::free_available(thread) is called by the testing routines. - */ - static std::vector& List(void) - { CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static std::vector list; - return list; - } -public: - /*! - Constructor called for each invocation of CPPAD_DISCRETE_FUNCTION. - - Put this object in the list of all objects for this class and set - the constant private data name_, f_, and index_. - - \param Name - is the user's name for this discrete function. - - \param f - user routine that implements this function for \c Base class. - - \par - This constructor can ont be used in parallel mode because it changes - the static object \c List. - */ - discrete(const char* Name, F f) : - name_(Name) - , f_(f) - , index_( List().size() ) - { - CPPAD_ASSERT_KNOWN( - ! thread_alloc::in_parallel() , - "discrete: First call the function *Name is in parallel mode." - ); - List().push_back(this); - } - - /*! - Implement the user call to ay = name(ax). - - \param ax - is the argument for this call. - - \return - the return value is called \c ay above. - */ - AD ad(const AD &ax) const - { AD ay; - - ay.value_ = f_(ax.value_); - if( Variable(ax) ) - { local::ADTape *tape = ax.tape_this(); - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::DisOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::DisOp) == 2 ); - - // put operand addresses in the tape - tape->Rec_.PutArg(index_, ax.taddr_); - // put operator in the tape - ay.taddr_ = tape->Rec_.PutOp(local::DisOp); - // make result a variable - ay.tape_id_ = tape->id_; - - CPPAD_ASSERT_UNKNOWN( Variable(ay) ); - } - return ay; - } - - /// Name corresponding to a discrete object - static const char* name(size_t index) - { return List()[index]->name_.c_str(); } - - /*! - Link from forward mode sweep to users routine - - \param index - index for this function in the list of all discrete object - - \param x - argument value at which to evaluate this function - */ - static Base eval(size_t index, const Base& x) - { - CPPAD_ASSERT_UNKNOWN(index < List().size() ); - - return List()[index]->f_(x); - } -}; - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/div.hpp b/ct_core/include/ct/external/cppad/core/div.hpp deleted file mode 100644 index 46110425c..000000000 --- a/ct_core/include/ct/external/cppad/core/div.hpp +++ /dev/null @@ -1,101 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_DIV_HPP -# define CPPAD_CORE_DIV_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD operator / (const AD &left , const AD &right) -{ - // compute the Base part - AD result; - result.value_ = left.value_ / right.value_; - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - // check if there is a recording in progress - local::ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return result; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = left.tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // result = variable / variable - CPPAD_ASSERT_KNOWN( - left.tape_id_ == right.tape_id_, - "Dividing AD objects that are" - " variables on different tapes." - ); - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::DivvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::DivvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(left.taddr_, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::DivvvOp); - // make result a variable - result.tape_id_ = tape_id; - } - else if( IdenticalOne(right.value_) ) - { // result = variable / 1 - result.make_variable(left.tape_id_, left.taddr_); - } - else - { // result = variable / parameter - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::DivvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::DivvpOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(left.taddr_, p); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::DivvpOp); - // make result a variable - result.tape_id_ = tape_id; - } - } - else if( var_right ) - { if( IdenticalZero(left.value_) ) - { // result = 0 / variable - } - else - { // result = parameter / variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::DivpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::DivpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left.value_); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::DivpvOp); - // make result a variable - result.tape_id_ = tape_id; - } - } - return result; -} - -// convert other cases into the case above -CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR(/) - - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/div_eq.hpp b/ct_core/include/ct/external/cppad/core/div_eq.hpp deleted file mode 100644 index 1ec73f9ef..000000000 --- a/ct_core/include/ct/external/cppad/core/div_eq.hpp +++ /dev/null @@ -1,93 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_DIV_EQ_HPP -# define CPPAD_CORE_DIV_EQ_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD& AD::operator /= (const AD &right) -{ - // compute the Base part - Base left; - left = value_; - value_ /= right.value_; - - // check if there is a recording in progress - local::ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return *this; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // this = variable / variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::DivvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::DivvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(taddr_, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(local::DivvvOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - else if( IdenticalOne( right.value_ ) ) - { // this = variable * 1 - } - else - { // this = variable / parameter - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::DivvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::DivvpOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(taddr_, p); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(local::DivvpOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - } - else if( var_right ) - { if( IdenticalZero(left) ) - { // this = 0 / variable - } - else - { // this = parameter / variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::DivpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::DivpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(local::DivpvOp); - // make this a variable - tape_id_ = tape_id; - } - } - return *this; -} - -CPPAD_FOLD_ASSIGNMENT_OPERATOR(/=) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/drivers.hpp b/ct_core/include/ct/external/cppad/core/drivers.hpp deleted file mode 100644 index ee753834f..000000000 --- a/ct_core/include/ct/external/cppad/core/drivers.hpp +++ /dev/null @@ -1,48 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_DRIVERS_HPP -# define CPPAD_CORE_DRIVERS_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Drivers$$ -$spell -$$ - - -$section First and Second Derivatives: Easy Drivers$$ -$mindex forward reverse$$ - - -$childtable% - cppad/core/jacobian.hpp% - cppad/core/for_one.hpp% - cppad/core/rev_one.hpp% - cppad/core/hessian.hpp% - cppad/core/for_two.hpp% - cppad/core/rev_two.hpp% - cppad/core/sparse_jacobian.hpp% - cppad/core/sparse_hessian.hpp -%$$ - -$end -*/ -# include -# include -# include -# include -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/core/epsilon.hpp b/ct_core/include/ct/external/cppad/core/epsilon.hpp deleted file mode 100644 index 68c46d64b..000000000 --- a/ct_core/include/ct/external/cppad/core/epsilon.hpp +++ /dev/null @@ -1,60 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_EPSILON_HPP -# define CPPAD_CORE_EPSILON_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ------------------------------------------------------------------------------- -$begin epsilon$$ -$spell - std - eps - CppAD - namespace - const -$$ - -$section Machine Epsilon For AD Types$$ - -$head Deprecated 2012-06-17$$ -This routine has been deprecated. -You should use the $cref numeric_limits$$ $code epsilon$$ instead. - -$head Syntax$$ -$icode%eps% = epsilon<%Float%>()%$$ - -$head Purpose$$ -Obtain the value of machine epsilon corresponding -to the type $icode%Float%$$. - -$head Float$$ -this type can either be $codei%AD<%Base%>%$$, -or it can be $icode Base$$ for any $codei%AD<%Base%>%$$ type. - -$head eps$$ -The result $icode eps$$ has prototype -$codei% - %Float% eps -%$$ - -$end ------------------------------------------------------------------------------- -*/ - -namespace CppAD { - - template - inline Type epsilon(void) - { return Type ( numeric_limits::epsilon() ); } - -} -# endif diff --git a/ct_core/include/ct/external/cppad/core/equal_op_seq.hpp b/ct_core/include/ct/external/cppad/core/equal_op_seq.hpp deleted file mode 100644 index 82b76f2a1..000000000 --- a/ct_core/include/ct/external/cppad/core/equal_op_seq.hpp +++ /dev/null @@ -1,120 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_EQUAL_OP_SEQ_HPP -# define CPPAD_CORE_EQUAL_OP_SEQ_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ------------------------------------------------------------------------------- -$begin EqualOpSeq$$ -$spell - Op - const - bool -$$ - - -$section Check if Two Value are Identically Equal$$ -$mindex EqualOpSeq operation sequence$$ - -$head Syntax$$ -$icode%b% = EqualOpSeq(%x%, %y%)%$$ - -$head Purpose$$ -Determine if two $icode x$$ and $icode y$$ are identically equal; i.e., -not only is $icode%x% == %y%$$ true, but -if they are $cref/variables/glossary/Variable/$$, -they correspond have the same -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Motivation$$ -Sometimes it is useful to cache information -and only recalculate when a function's arguments change. -In the case of AD variables, -it may be important not only when the argument values are equal, -but when they are related to the -$cref/independent variables/glossary/Tape/Independent Variable/$$ -by the same operation sequence. -After the assignment -$codei% - %y% = %x% -%$$ -these two AD objects would not only have equal values, -but would also correspond to the same operation sequence. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const AD<%Base%> &%x% -%$$ - -$head y$$ -The argument $icode y$$ has prototype -$codei% - const AD<%Base%> &%y% -%$$ - -$head b$$ -The result $icode b$$ has prototype -$codei% - bool %b% -%$$ -The result is true if and only if one of the following cases holds: - -$list number$$ -Both $icode x$$ and $icode y$$ are variables -and correspond to the same operation sequence. -$lnext -Both $icode x$$ and $icode y$$ are parameters, -$icode Base$$ is an AD type, -and $codei%EqualOpSeq( Value(%x%) , Value(%y%) )%$$ is true. -$lnext -Both $icode x$$ and $icode y$$ are parameters, -$icode Base$$ is not an AD type, -and $icode%x% == %y%%$$ is true. -$lend - - -$head Example$$ -$children% - example/equal_op_seq.cpp -%$$ -The file -$cref equal_op_seq.cpp$$ -contains an example and test of $code EqualOpSeq$$. -It returns true if it succeeds and false otherwise. - - -$end ------------------------------------------------------------------------------- -*/ - - -namespace CppAD { - template - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION - bool EqualOpSeq(const AD &x, const AD &y) - { - if( Parameter(x) ) - { if( Parameter(y) ) - return EqualOpSeq(x.value_, y.value_); - else return false; - } - else if( Parameter(y) ) - return false; - - return (x.taddr_ == y.taddr_); - } - -} - -# endif diff --git a/ct_core/include/ct/external/cppad/core/erf.hpp b/ct_core/include/ct/external/cppad/core/erf.hpp deleted file mode 100644 index 2cddaa6ad..000000000 --- a/ct_core/include/ct/external/cppad/core/erf.hpp +++ /dev/null @@ -1,107 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_ERF_HPP -# define CPPAD_CORE_ERF_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin erf$$ -$spell - erf - const - Vec - std - cmath - CppAD - Vedder -$$ -$section The Error Function$$ - -$head Syntax$$ -$icode%y% = erf(%x%)%$$ - -$head Description$$ -Returns the value of the error function which is defined by -$latex \[ -{\rm erf} (x) = \frac{2}{ \sqrt{\pi} } \int_0^x \exp( - t * t ) \; {\bf d} t -\] $$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head CPPAD_USE_CPLUSPLUS_2011$$ - -$subhead true$$ -If this preprocessor symbol is true ($code 1$$), -and $icode x$$ is an AD type, -this is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$subhead false$$ -If this preprocessor symbol is false ($code 0$$), -CppAD uses a fast approximation (few numerical operations) -with relative error bound $latex 4 \times 10^{-4}$$; see -Vedder, J.D., -$icode Simple approximations for the error function and its inverse$$, -American Journal of Physics, -v 55, -n 8, -1987, -p 762-3. - -$head Example$$ -$children% - example/erf.cpp -%$$ -The file -$cref erf.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ -# include -# if ! CPPAD_USE_CPLUSPLUS_2011 - -// BEGIN CppAD namespace -namespace CppAD { - -template -Type erf_template(const Type &x) -{ using CppAD::exp; - const Type a = static_cast(993./880.); - const Type b = static_cast(89./880.); - - return tanh( (a + b * x * x) * x ); -} - -inline float erf(const float &x) -{ return erf_template(x); } - -inline double erf(const double &x) -{ return erf_template(x); } - -template -inline AD erf(const AD &x) -{ return erf_template(x); } - -template -inline AD erf(const VecAD_reference &x) -{ return erf_template( x.ADBase() ); } - - -} // END CppAD namespace - -# endif // CPPAD_USE_CPLUSPLUS_2011 -# endif // CPPAD_ERF_INCLUDED diff --git a/ct_core/include/ct/external/cppad/core/expm1.hpp b/ct_core/include/ct/external/cppad/core/expm1.hpp deleted file mode 100644 index 79800dfcb..000000000 --- a/ct_core/include/ct/external/cppad/core/expm1.hpp +++ /dev/null @@ -1,97 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_EXPM1_HPP -# define CPPAD_CORE_EXPM1_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin expm1$$ -$spell - exp - expm1 - const - Vec - std - cmath - CppAD -$$ -$section The Exponential Function Minus One: expm1$$ - -$head Syntax$$ -$icode%y% = expm1(%x%)%$$ - -$head Description$$ -Returns the value of the exponential function minus one which is defined -by $icode%y% == exp(%x%) - 1%$$. - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head CPPAD_USE_CPLUSPLUS_2011$$ - -$subhead true$$ -If this preprocessor symbol is true ($code 1$$), -and $icode x$$ is an AD type, -this is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$subhead false$$ -If this preprocessor symbol is false ($code 0$$), -CppAD uses the representation -$latex \[ -\R{expm1} (x) = \exp(x) - 1 -\] $$ -to compute this function. - -$head Example$$ -$children% - example/expm1.cpp -%$$ -The file -$cref expm1.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ -# include -# if ! CPPAD_USE_CPLUSPLUS_2011 - -// BEGIN CppAD namespace -namespace CppAD { - -template -Type expm1_template(const Type &x) -{ return CppAD::exp(x) - Type(1); -} - -inline float expm1(const float &x) -{ return expm1_template(x); } - -inline double expm1(const double &x) -{ return expm1_template(x); } - -template -inline AD expm1(const AD &x) -{ return expm1_template(x); } - -template -inline AD expm1(const VecAD_reference &x) -{ return expm1_template( x.ADBase() ); } - - -} // END CppAD namespace - -# endif // CPPAD_USE_CPLUSPLUS_2011 -# endif // CPPAD_EXPM1_INCLUDED diff --git a/ct_core/include/ct/external/cppad/core/for_one.hpp b/ct_core/include/ct/external/cppad/core/for_one.hpp deleted file mode 100644 index 45cfd4db5..000000000 --- a/ct_core/include/ct/external/cppad/core/for_one.hpp +++ /dev/null @@ -1,165 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_FOR_ONE_HPP -# define CPPAD_CORE_FOR_ONE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin ForOne$$ -$spell - dy - typename - Taylor - const -$$ - - - - -$section First Order Partial Derivative: Driver Routine$$ -$mindex easy$$ - -$head Syntax$$ -$icode%dy% = %f%.ForOne(%x%, %j%)%$$ - - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -The syntax above sets $icode dy$$ to the -partial of $latex F$$ with respect to $latex x_j$$; i.e., -$latex \[ -dy -= \D{F}{ x_j } (x) -= \left[ - \D{ F_0 }{ x_j } (x) , \cdots , \D{ F_{m-1} }{ x_j } (x) -\right] -\] $$ - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/ForOne Uses Forward/ForOne/ForOne Uses Forward/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -(see $cref/Vector/ForOne/Vector/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the partial derivative. - -$head j$$ -The argument $icode j$$ has prototype -$codei% - size_t %j% -%$$ -an is less than $icode n$$, -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies the component of $icode F$$ -for which we are computing the partial derivative. - -$head dy$$ -The result $icode dy$$ has prototype -$codei% - %Vector% %dy% -%$$ -(see $cref/Vector/ForOne/Vector/$$ below) -and its size is $latex m$$, the dimension of the -$cref/range/seq_property/Range/$$ space for $icode f$$. -The value of $icode dy$$ is the partial of $latex F$$ with respect to -$latex x_j$$ evaluated at $icode x$$; i.e., -for $latex i = 0 , \ldots , m - 1$$ -$latex \[. - dy[i] = \D{ F_i }{ x_j } ( x ) -\] $$ - - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Base$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head ForOne Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to $code ForOne$$, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0,%x%)%$$ -and the other coefficients are unspecified. - -$head Example$$ -$children% - example/for_one.cpp -%$$ -The routine -$cref/ForOne/for_one.cpp/$$ is both an example and test. -It returns $code true$$, if it succeeds and $code false$$ otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -template -Vector ADFun::ForOne(const Vector &x, size_t j) -{ size_t j1; - - size_t n = Domain(); - size_t m = Range(); - - // check Vector is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( - x.size() == n, - "ForOne: Length of x not equal domain dimension for f" - ); - CPPAD_ASSERT_KNOWN( - j < n, - "ForOne: the index j is not less than domain dimension for f" - ); - - // point at which we are evaluating the second partials - Forward(0, x); - - // direction in which are are taking the derivative - Vector dx(n); - for(j1 = 0; j1 < n; j1++) - dx[j1] = Base(0); - dx[j] = Base(1); - - // dimension the return value - Vector dy(m); - - // compute the return value - dy = Forward(1, dx); - - return dy; -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/for_sparse_hes.hpp b/ct_core/include/ct/external/cppad/core/for_sparse_hes.hpp deleted file mode 100644 index a5a7f152d..000000000 --- a/ct_core/include/ct/external/cppad/core/for_sparse_hes.hpp +++ /dev/null @@ -1,560 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_FOR_SPARSE_HES_HPP -# define CPPAD_CORE_FOR_SPARSE_HES_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin ForSparseHes$$ -$spell - Andrea Walther - std - VecAD - Jacobian - Jac - Hessian - Hes - const - Bool - Dep - proportional - var - cpp -$$ - -$section Hessian Sparsity Pattern: Forward Mode$$ - -$head Syntax$$ -$icode%h% = %f%.ForSparseHes(%r%, %s%) -%$$ - -$head Purpose$$ -We use $latex F : \B{R}^n \rightarrow \B{R}^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -we define -$latex \[ -\begin{array}{rcl} -H(x) -& = & \partial_x \left[ \partial_u S \cdot F[ x + R \cdot u ] \right]_{u=0} -\\ -& = & R^\R{T} \cdot (S \cdot F)^{(2)} ( x ) \cdot R -\end{array} -\] $$ -Where $latex R \in \B{R}^{n \times n}$$ is a diagonal matrix -and $latex S \in \B{R}^{1 \times m}$$ is a row vector. -Given a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the diagonal of $latex R$$ and the vector $latex S$$, -$code ForSparseHes$$ returns a sparsity pattern for the $latex H(x)$$. - -$head f$$ -The object $icode f$$ has prototype -$codei% - const ADFun<%Base%> %f% -%$$ - -$head x$$ -If the operation sequence in $icode f$$ is -$cref/independent/glossary/Operation/Independent/$$ of -the independent variables in $latex x \in B^n$$, -the sparsity pattern is valid for all values of -(even if it has $cref CondExp$$ or $cref VecAD$$ operations). - -$head r$$ -The argument $icode r$$ has prototype -$codei% - const %VectorSet%& %r% -%$$ -(see $cref/VectorSet/ForSparseHes/VectorSet/$$ below) -If it has elements of type $code bool$$, -its size is $latex n$$. -If it has elements of type $code std::set$$, -its size is one and all the elements of $icode%s%[0]%$$ -are between zero and $latex n - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the diagonal of $latex R$$. -The fewer non-zero elements in this sparsity pattern, -the faster the calculation should be and the more sparse -$latex H(x)$$ should be. - -$head s$$ -The argument $icode s$$ has prototype -$codei% - const %VectorSet%& %s% -%$$ -(see $cref/VectorSet/ForSparseHes/VectorSet/$$ below) -If it has elements of type $code bool$$, -its size is $latex m$$. -If it has elements of type $code std::set$$, -its size is one and all the elements of $icode%s%[0]%$$ -are between zero and $latex m - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the vector $icode S$$. -The fewer non-zero elements in this sparsity pattern, -the faster the calculation should be and the more sparse -$latex H(x)$$ should be. - -$head h$$ -The result $icode h$$ has prototype -$codei% - %VectorSet%& %h% -%$$ -(see $cref/VectorSet/ForSparseHes/VectorSet/$$ below). -If $icode h$$ has elements of type $code bool$$, -its size is $latex n * n$$. -If it has elements of type $code std::set$$, -its size is $latex n$$ and all the set elements are between -zero and $icode%n%-1%$$ inclusive. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex H(x)$$. - -$head VectorSet$$ -The type $icode VectorSet$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code bool$$ or $code std::set$$; -see $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for a discussion -of the difference. -The type of the elements of -$cref/VectorSet/ForSparseHes/VectorSet/$$ must be the -same as the type of the elements of $icode r$$. - -$head Algorithm$$ -See Algorithm II in -$italic Computing sparse Hessians with automatic differentiation$$ -by Andrea Walther. -Note that $icode s$$ provides the information so that -'dead ends' are not included in the sparsity pattern. - -$head Example$$ -$children% - example/for_sparse_hes.cpp -%$$ -The file -$cref for_sparse_hes.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------ -*/ -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file for_sparse_hes.hpp -Forward mode Hessian sparsity patterns. -*/ -// =========================================================================== -// ForSparseHesCase -/*! -Private helper function for ForSparseHes(q, s) bool sparsity. - -All of the description in the public member function ForSparseHes(q, s) -applies. - -\param set_type -is a \c bool value. This argument is used to dispatch to the proper source -code depending on the vlaue of \c VectorSet::value_type. - -\param r -See \c ForSparseHes(r, s). - -\param s -See \c ForSparseHes(r, s). - -\param h -is the return value for the corresponging call to \c ForSparseJac(q, s). -*/ -template -template -void ADFun::ForSparseHesCase( - bool set_type , - const VectorSet& r , - const VectorSet& s , - VectorSet& h ) -{ size_t n = Domain(); - size_t m = Range(); - // - // check Vector is Simple VectorSet class with bool elements - CheckSimpleVector(); - // - CPPAD_ASSERT_KNOWN( - size_t(r.size()) == n, - "ForSparseHes: size of r is not equal to\n" - "domain dimension for ADFun object." - ); - CPPAD_ASSERT_KNOWN( - size_t(s.size()) == m, - "ForSparseHes: size of s is not equal to\n" - "range dimension for ADFun object." - ); - // - // sparsity pattern corresponding to r - local::sparse_pack for_jac_sparsity; - for_jac_sparsity.resize(num_var_tape_, n + 1); - for(size_t i = 0; i < n; i++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[i] < n + 1 ); - // ind_taddr_[i] is operator taddr for i-th independent variable - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[i] ) == local::InvOp ); - // - if( r[i] ) - for_jac_sparsity.add_element( ind_taddr_[i], ind_taddr_[i] ); - } - // compute forward Jacobiain sparsity pattern - bool dependency = false; - local::ForJacSweep( - dependency, - n, - num_var_tape_, - &play_, - for_jac_sparsity - ); - // sparsity pattern correspnding to s - local::sparse_pack rev_jac_sparsity; - rev_jac_sparsity.resize(num_var_tape_, 1); - for(size_t i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - if( s[i] ) - rev_jac_sparsity.add_element( dep_taddr_[i], 0); - } - // compute reverse sparsity pattern for dependency analysis - // (note that we are only want non-zero derivatives not true dependency) - local::RevJacSweep( - dependency, - n, - num_var_tape_, - &play_, - rev_jac_sparsity - ); - // vector of sets that will hold the forward Hessain values - local::sparse_pack for_hes_sparsity; - for_hes_sparsity.resize(n+1, n+1); - // - // compute the Hessian sparsity patterns - local::ForHesSweep( - n, - num_var_tape_, - &play_, - for_jac_sparsity, - rev_jac_sparsity, - for_hes_sparsity - ); - // initialize return values corresponding to independent variables - h.resize(n * n); - for(size_t i = 0; i < n; i++) - { for(size_t j = 0; j < n; j++) - h[ i * n + j ] = false; - } - // copy to result pattern - CPPAD_ASSERT_UNKNOWN( for_hes_sparsity.end() == n+1 ); - for(size_t i = 0; i < n; i++) - { // ind_taddr_[i] is operator taddr for i-th independent variable - CPPAD_ASSERT_UNKNOWN( ind_taddr_[i] == i + 1 ); - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[i] ) == local::InvOp ); - - // extract the result from for_hes_sparsity - local::sparse_pack::const_iterator itr(for_hes_sparsity, ind_taddr_[i] ); - size_t j = *itr; - while( j < for_hes_sparsity.end() ) - { CPPAD_ASSERT_UNKNOWN( 0 < j ) - h[ i * n + (j-1) ] = true; - j = *(++itr); - } - } -} -/*! -Private helper function for ForSparseHes(q, s) set sparsity. - -All of the description in the public member function ForSparseHes(q, s) -applies. - -\param set_type -is a \c std::set value. -This argument is used to dispatch to the proper source -code depending on the vlaue of \c VectorSet::value_type. - -\param r -See \c ForSparseHes(r, s). - -\param s -See \c ForSparseHes(q, s). - -\param h -is the return value for the corresponging call to \c ForSparseJac(q, s). -*/ -template -template -void ADFun::ForSparseHesCase( - const std::set& set_type , - const VectorSet& r , - const VectorSet& s , - VectorSet& h ) -{ size_t n = Domain(); -# ifndef NDEBUG - size_t m = Range(); -# endif - std::set::const_iterator itr_1; - // - // check VectorSet is Simple Vector class with sets for elements - CheckSimpleVector, VectorSet>( - local::one_element_std_set(), local::two_element_std_set() - ); - CPPAD_ASSERT_KNOWN( - r.size() == 1, - "ForSparseHes: size of s is not equal to one." - ); - CPPAD_ASSERT_KNOWN( - s.size() == 1, - "ForSparseHes: size of s is not equal to one." - ); - // - // sparsity pattern corresponding to r - local::sparse_list for_jac_sparsity; - for_jac_sparsity.resize(num_var_tape_, n + 1); - itr_1 = r[0].begin(); - while( itr_1 != r[0].end() ) - { size_t i = *itr_1++; - CPPAD_ASSERT_UNKNOWN( ind_taddr_[i] < n + 1 ); - // ind_taddr_[i] is operator taddr for i-th independent variable - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[i] ) == local::InvOp ); - // - for_jac_sparsity.add_element( ind_taddr_[i], ind_taddr_[i] ); - } - // compute forward Jacobiain sparsity pattern - bool dependency = false; - local::ForJacSweep( - dependency, - n, - num_var_tape_, - &play_, - for_jac_sparsity - ); - // sparsity pattern correspnding to s - local::sparse_list rev_jac_sparsity; - rev_jac_sparsity.resize(num_var_tape_, 1); - itr_1 = s[0].begin(); - while( itr_1 != s[0].end() ) - { size_t i = *itr_1++; - CPPAD_ASSERT_KNOWN( - i < m, - "ForSparseHes: an element of the set s[0] has value " - "greater than or equal m" - ); - CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - rev_jac_sparsity.add_element( dep_taddr_[i], 0); - } - // - // compute reverse sparsity pattern for dependency analysis - // (note that we are only want non-zero derivatives not true dependency) - local::RevJacSweep( - dependency, - n, - num_var_tape_, - &play_, - rev_jac_sparsity - ); - // - // vector of sets that will hold reverse Hessain values - local::sparse_list for_hes_sparsity; - for_hes_sparsity.resize(n+1, n+1); - // - // compute the Hessian sparsity patterns - local::ForHesSweep( - n, - num_var_tape_, - &play_, - for_jac_sparsity, - rev_jac_sparsity, - for_hes_sparsity - ); - // return values corresponding to independent variables - // j is index corresponding to reverse mode partial - h.resize(n); - CPPAD_ASSERT_UNKNOWN( for_hes_sparsity.end() == n+1 ); - for(size_t i = 0; i < n; i++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[i] == i + 1 ); - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[i] ) == local::InvOp ); - - // extract the result from for_hes_sparsity - local::sparse_list::const_iterator itr_2(for_hes_sparsity, ind_taddr_[i] ); - size_t j = *itr_2; - while( j < for_hes_sparsity.end() ) - { CPPAD_ASSERT_UNKNOWN( 0 < j ) - h[i].insert(j-1); - j = *(++itr_2); - } - } -} - -// =========================================================================== -// ForSparseHes - -/*! -User API for Hessian sparsity patterns using reverse mode. - -The C++ source code corresponding to this operation is -\verbatim - h = f.ForSparseHes(q, r) -\endverbatim - -\tparam Base -is the base type for this recording. - -\tparam VectorSet -is a simple vector with elements of type \c bool -or \c std::set. - -\param r -is a vector with size \c n that specifies the sparsity pattern -for the diagonal of the matrix \f$ R \f$, -where \c n is the number of independent variables -corresponding to the operation sequence stored in \a play. - -\param s -is a vector with size \c m that specifies the sparsity pattern -for the vector \f$ S \f$, -where \c m is the number of dependent variables -corresponding to the operation sequence stored in \a play. - -\return -The return vector is a sparsity pattern for \f$ H(x) \f$ -\f[ - H(x) = R^T ( S * F)^{(2)} (x) R -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \a x is any argument value. -*/ - -template -template -VectorSet ADFun::ForSparseHes( - const VectorSet& r, const VectorSet& s -) -{ VectorSet h; - typedef typename VectorSet::value_type Set_type; - - // Should check to make sure q is same as in previous call to - // forward sparse Jacobian. - ForSparseHesCase( - Set_type() , - r , - s , - h - ); - - return h; -} -// =========================================================================== -// ForSparseHesCheckpoint -/*! -Hessian sparsity patterns calculation used by checkpoint functions. - -\tparam Base -is the base type for this recording. - -\param r -is a vector with size n that specifies the sparsity pattern -for the diagonal of \f$ R \f$, -where n is the number of independent variables -corresponding to the operation sequence stored in play_. - -\param s -is a vector with size m that specifies the sparsity pattern -for the vector \f$ S \f$, -where m is the number of dependent variables -corresponding to the operation sequence stored in play_. - -\param h -The input size and elements of h do not matter. -On output, h is the sparsity pattern for the matrix \f$ H(x) R \f$. - -\par Assumptions -The forward jacobian sparsity pattern must be currently stored -in this ADFUN object. -*/ - -// The checkpoint class is not yet using forward sparse Hessians. -# ifdef CPPAD_NOT_DEFINED -template -void ADFun::ForSparseHesCheckpoint( - vector& r , - vector& s , - local::sparse_list& h ) -{ - size_t n = Domain(); - size_t m = Range(); - - // checkpoint functions should get this right - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_pack_.n_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_set_.n_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( s.size() == m ); - - // Array that holds the reverse Jacobiain dependcy flags. - // Initialize as true for dependent variables, flase for others. - local::pod_vector RevJac; - RevJac.extend(num_var_tape_); - for(size_t i = 0; i < num_var_tape_; i++) - RevJac[i] = false; - for(size_t i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ) - RevJac[ dep_taddr_[i] ] = s[i]; - } - - // holds forward Hessian sparsity pattern for all variables - local::sparse_list for_hes_sparsity; - for_hes_sparsity.resize(n+1, n+1); - - // compute Hessian sparsity pattern for all variables - local::ForHesSweep( - n, - num_var_tape_, - &play_, - for_jac_sparse_set_, - RevJac.data(), - for_hes_sparsity - ); - - // dimension the return value - if( transpose ) - h.resize(n, n); - else - h.resize(n, n); - - // j is index corresponding to reverse mode partial - for(size_t j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] < num_var_tape_ ); - - // ind_taddr_[j] is operator taddr for j-th independent variable - CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] == j + 1 ); - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == local::InvOp ); - - // extract the result from for_hes_sparsity - CPPAD_ASSERT_UNKNOWN( for_hes_sparsity.end() == q ); - local::sparse_list::const_iterator itr(for_hes_sparsity, .j + 1); - size_t i = *itr; - while( i < q ) - { if( transpose ) - h.add_element(j, i); - else h.add_element(i, j); - i = *(++itr); - } - } -} -# endif - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/for_sparse_jac.hpp b/ct_core/include/ct/external/cppad/core/for_sparse_jac.hpp deleted file mode 100644 index a4e0574f4..000000000 --- a/ct_core/include/ct/external/cppad/core/for_sparse_jac.hpp +++ /dev/null @@ -1,729 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_FOR_SPARSE_JAC_HPP -# define CPPAD_CORE_FOR_SPARSE_JAC_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin ForSparseJac$$ -$spell - std - var - Jacobian - Jac - const - Bool - proportional - VecAD - CondExpRel - optimizer - cpp -$$ - -$section Jacobian Sparsity Pattern: Forward Mode$$ - -$head Syntax$$ -$icode%s% = %f%.ForSparseJac(%q%, %r%) -%$$ -$icode%s% = %f%.ForSparseJac(%q%, %r%, %transpose%, %dependency%)%$$ - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -For a fixed $latex n \times q$$ matrix $latex R$$, -the Jacobian of $latex F[ x + R * u ]$$ -with respect to $latex u$$ at $latex u = 0$$ is -$latex \[ - S(x) = F^{(1)} ( x ) * R -\] $$ -Given a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for $latex R$$, -$code ForSparseJac$$ returns a sparsity pattern for the $latex S(x)$$. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$. -After a call to $code ForSparseJac$$, the sparsity pattern -for each of the variables in the operation sequence -is held in $icode f$$ (for possible later use by $cref RevSparseHes$$). -These sparsity patterns are stored with elements of type $code bool$$ -or elements of type $code std::set$$ -(see $cref/VectorSet/ForSparseJac/VectorSet/$$ below). - -$subhead size_forward_bool$$ -After $code ForSparseJac$$, if $icode k$$ is a $code size_t$$ object, -$codei% - %k% = %f%.size_forward_bool() -%$$ -sets $icode k$$ to the amount of memory (in unsigned character units) -used to store the sparsity pattern with elements of type $code bool$$ -in the function object $icode f$$. -If the sparsity patterns for the previous $code ForSparseJac$$ used -elements of type $code bool$$, -the return value for $code size_forward_bool$$ will be non-zero. -Otherwise, its return value will be zero. -This sparsity pattern is stored for use by $cref RevSparseHes$$ and -when it is not longer needed, it can be deleted -(and the corresponding memory freed) using -$codei% - %f%.size_forward_bool(0) -%$$ -After this call, $icode%f%.size_forward_bool()%$$ will return zero. - -$subhead size_forward_set$$ -After $code ForSparseJac$$, if $icode k$$ is a $code size_t$$ object, -$codei% - %k% = %f%.size_forward_set() -%$$ -sets $icode s$$ to the total number of elements in all the sets corresponding -to the sparsity pattern stored in the function object $icode f$$. -If the sparsity patterns for this operation use elements of type $code bool$$, -the return value for $code size_forward_set$$ will be zero. -Otherwise, its return value will be non-zero -(unless the entire sparsity pattern is false). -This sparsity pattern is stored for use by $cref RevSparseHes$$ and -when it is not longer needed, it can be deleted -(and the corresponding memory freed) using -$codei% - %f%.size_forward_set(0) -%$$ -After this call, $icode%f%.size_forward_set()%$$ will return zero. - -$head x$$ -If the operation sequence in $icode f$$ is -$cref/independent/glossary/Operation/Independent/$$ of -the independent variables in $latex x \in B^n$$, -the sparsity pattern is valid for all values of -(even if it has $cref CondExp$$ or $cref VecAD$$ operations). - -$head q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of columns in -$latex R \in B^{n \times q}$$ and the Jacobian -$latex S(x) \in B^{m \times q}$$. - -$head transpose$$ -The argument $icode transpose$$ has prototype -$codei% - bool %transpose% -%$$ -The default value $code false$$ is used when $icode transpose$$ is not present. - -$head dependency$$ -The argument $icode dependency$$ has prototype -$codei% - bool %dependency% -%$$ -If $icode dependency$$ is true, -the $cref/dependency pattern/dependency.cpp/Dependency Pattern/$$ -(instead of sparsity pattern) is computed. - -$head r$$ -The argument $icode r$$ has prototype -$codei% - const %VectorSet%& %r% -%$$ -see $cref/VectorSet/ForSparseJac/VectorSet/$$ below. - -$subhead transpose false$$ -If $icode r$$ has elements of type $code bool$$, -its size is $latex n * q$$. -If it has elements of type $code std::set$$, -its size is $latex n$$ and all the set elements must be between -zero and $icode%q%-1%$$ inclusive. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex R \in B^{n \times q}$$. - -$subhead transpose true$$ -If $icode r$$ has elements of type $code bool$$, -its size is $latex q * n$$. -If it has elements of type $code std::set$$, -its size is $latex q$$ and all the set elements must be between -zero and $icode%n%-1%$$ inclusive. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex R^\R{T} \in B^{q \times n}$$. - -$head s$$ -The return value $icode s$$ has prototype -$codei% - %VectorSet% %s% -%$$ -see $cref/VectorSet/ForSparseJac/VectorSet/$$ below. - -$subhead transpose false$$ -If $icode s$$ has elements of type $code bool$$, -its size is $latex m * q$$. -If it has elements of type $code std::set$$, -its size is $latex m$$ and all its set elements are between -zero and $icode%q%-1%$$ inclusive. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex S(x) \in B^{m \times q}$$. - -$subhead transpose true$$ -If $icode s$$ has elements of type $code bool$$, -its size is $latex q * m$$. -If it has elements of type $code std::set$$, -its size is $latex q$$ and all its set elements are between -zero and $icode%m%-1%$$ inclusive. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex S(x)^\R{T} \in B^{q \times m}$$. - -$head VectorSet$$ -The type $icode VectorSet$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code bool$$ or $code std::set$$; -see $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for a discussion -of the difference. - -$head Entire Sparsity Pattern$$ -Suppose that $latex q = n$$ and -$latex R$$ is the $latex n \times n$$ identity matrix. -In this case, -the corresponding value for $icode s$$ is a -sparsity pattern for the Jacobian $latex S(x) = F^{(1)} ( x )$$. - -$head Example$$ -$children% - example/for_sparse_jac.cpp -%$$ -The file -$cref for_sparse_jac.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. -The file -$cref/sparsity_sub.cpp/sparsity_sub.cpp/ForSparseJac/$$ -contains an example and test of using $code ForSparseJac$$ -to compute the sparsity pattern for a subset of the Jacobian. - -$end ------------------------------------------------------------------------------ -*/ - -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file for_sparse_jac.hpp -Forward mode Jacobian sparsity patterns. -*/ -// --------------------------------------------------------------------------- -/*! -Private helper function for ForSparseJac(q, r) boolean sparsity patterns. - -All of the description in the public member function ForSparseJac(q, r) -applies. - -\param set_type -is a \c bool value. This argument is used to dispatch to the proper source -code depending on the value of \c VectorSet::value_type. - -\param transpose -See \c ForSparseJac(q, r, transpose, dependency). - -\param dependency -See \c ForSparseJac(q, r, transpose, dependency). - -\param q -See \c ForSparseJac(q, r, transpose, dependency). - -\param r -See \c ForSparseJac(q, r, transpose, dependency). - -\param s -is the return value for the corresponding call to \c ForSparseJac(q, r). -*/ - -template -template -void ADFun::ForSparseJacCase( - bool set_type , - bool transpose , - bool dependency , - size_t q , - const VectorSet& r , - VectorSet& s ) -{ size_t m = Range(); - size_t n = Domain(); - - // check VectorSet is Simple Vector class with bool elements - CheckSimpleVector(); - - // dimension size of result vector - s.resize( m * q ); - - // temporary indices - size_t i, j; - // - CPPAD_ASSERT_KNOWN( - q > 0, - "ForSparseJac: q is not greater than zero" - ); - CPPAD_ASSERT_KNOWN( - size_t(r.size()) == n * q, - "ForSparseJac: size of r is not equal to\n" - "q times domain dimension for ADFun object." - ); - // - // allocate memory for the requested sparsity calculation result - for_jac_sparse_pack_.resize(num_var_tape_, q); - - // set values corresponding to independent variables - for(i = 0; i < n; i++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[i] < num_var_tape_ ); - // ind_taddr_[i] is operator taddr for i-th independent variable - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[i] ) == local::InvOp ); - - // set bits that are true - if( transpose ) - { for(j = 0; j < q; j++) if( r[ j * n + i ] ) - for_jac_sparse_pack_.add_element( ind_taddr_[i], j); - } - else - { for(j = 0; j < q; j++) if( r[ i * q + j ] ) - for_jac_sparse_pack_.add_element( ind_taddr_[i], j); - } - } - - // evaluate the sparsity patterns - local::ForJacSweep( - dependency, - n, - num_var_tape_, - &play_, - for_jac_sparse_pack_ - ); - - // return values corresponding to dependent variables - CPPAD_ASSERT_UNKNOWN( size_t(s.size()) == m * q ); - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - - // extract the result from for_jac_sparse_pack_ - if( transpose ) - { for(j = 0; j < q; j++) - s[ j * m + i ] = false; - } - else - { for(j = 0; j < q; j++) - s[ i * q + j ] = false; - } - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_pack_.end() == q ); - local::sparse_pack::const_iterator itr(for_jac_sparse_pack_, dep_taddr_[i] ); - j = *itr; - while( j < q ) - { if( transpose ) - s[j * m + i] = true; - else s[i * q + j] = true; - j = *(++itr); - } - } -} -// --------------------------------------------------------------------------- -/*! -Private helper function for \c ForSparseJac(q, r) set sparsity. - -All of the description in the public member function \c ForSparseJac(q, r) -applies. - -\param set_type -is a \c std::set object. -This argument is used to dispatch to the proper source -code depending on the value of \c VectorSet::value_type. - -\param transpose -See \c ForSparseJac(q, r, transpose, dependency). - -\param dependency -See \c ForSparseJac(q, r, transpose, dependency). - -\param q -See \c ForSparseJac(q, r, transpose, dependency). - -\param r -See \c ForSparseJac(q, r, transpose, dependency). - -\param s -is the return value for the corresponding call to \c ForSparseJac(q, r). -*/ -template -template -void ADFun::ForSparseJacCase( - const std::set& set_type , - bool transpose , - bool dependency , - size_t q , - const VectorSet& r , - VectorSet& s ) -{ size_t m = Range(); - size_t n = Domain(); - - // check VectorSet is Simple Vector class with sets for elements - CheckSimpleVector, VectorSet>( - local::one_element_std_set(), local::two_element_std_set() - ); - - // dimension size of result vector - if( transpose ) - s.resize(q); - else s.resize( m ); - - // temporary indices - size_t i, j; - std::set::const_iterator itr_1; - // - CPPAD_ASSERT_KNOWN( - q > 0, - "ForSparseJac: q is not greater than zero" - ); - CPPAD_ASSERT_KNOWN( - size_t(r.size()) == n || transpose, - "ForSparseJac: size of r is not equal to n and transpose is false." - ); - CPPAD_ASSERT_KNOWN( - size_t(r.size()) == q || ! transpose, - "ForSparseJac: size of r is not equal to q and transpose is true." - ); - // - // allocate memory for the requested sparsity calculation - for_jac_sparse_set_.resize(num_var_tape_, q); - - // set values corresponding to independent variables - if( transpose ) - { for(i = 0; i < q; i++) - { // add the elements that are present - itr_1 = r[i].begin(); - while( itr_1 != r[i].end() ) - { j = *itr_1++; - CPPAD_ASSERT_KNOWN( - j < n, - "ForSparseJac: transpose is true and element of the set\n" - "r[j] has value greater than or equal n." - ); - CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] < num_var_tape_ ); - // operator for j-th independent variable - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == local::InvOp ); - for_jac_sparse_set_.add_element( ind_taddr_[j], i); - } - } - } - else - { for(i = 0; i < n; i++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[i] < num_var_tape_ ); - // ind_taddr_[i] is operator taddr for i-th independent variable - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[i] ) == local::InvOp ); - - // add the elements that are present - itr_1 = r[i].begin(); - while( itr_1 != r[i].end() ) - { j = *itr_1++; - CPPAD_ASSERT_KNOWN( - j < q, - "ForSparseJac: an element of the set r[i] " - "has value greater than or equal q." - ); - for_jac_sparse_set_.add_element( ind_taddr_[i], j); - } - } - } - // evaluate the sparsity patterns - local::ForJacSweep( - dependency, - n, - num_var_tape_, - &play_, - for_jac_sparse_set_ - ); - - // return values corresponding to dependent variables - CPPAD_ASSERT_UNKNOWN( size_t(s.size()) == m || transpose ); - CPPAD_ASSERT_UNKNOWN( size_t(s.size()) == q || ! transpose ); - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - - // extract results from for_jac_sparse_set_ - // and add corresponding elements to sets in s - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_set_.end() == q ); - local::sparse_list::const_iterator itr_2(for_jac_sparse_set_, dep_taddr_[i] ); - j = *itr_2; - while( j < q ) - { if( transpose ) - s[j].insert(i); - else s[i].insert(j); - j = *(++itr_2); - } - } -} -// --------------------------------------------------------------------------- - -/*! -User API for Jacobian sparsity patterns using forward mode. - -The C++ source code corresponding to this operation is -\verbatim - s = f.ForSparseJac(q, r, transpose, dependency) -\endverbatim - -\tparam Base -is the base type for this recording. - -\tparam VectorSet -is a simple vector with elements of type \c bool -or \c std::set. - -\param q -is the number of columns in the matrix \f$ R \f$. - -\param r -is a sparsity pattern for the matrix \f$ R \f$. - -\param transpose -are sparsity patterns for \f$ R \f$ and \f$ S(x) \f$ transposed. - -\param dependency -Are the derivatives with respect to left and right of the expression below -considered to be non-zero: -\code - CondExpRel(left, right, if_true, if_false) -\endcode -This is used by the optimizer to obtain the correct dependency relations. - -\return -The value of \c transpose is false (true), -the return value is a sparsity pattern for \f$ S(x) \f$ (\f$ S(x)^T \f$) where -\f[ - S(x) = F^{(1)} (x) * R -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \a x is any argument value. -If \c VectorSet::value_type is \c bool, -the return value has size \f$ m * q \f$ (\f$ q * m \f$). -where \c m is the number of dependent variables -corresponding to the operation sequence stored in \c f. -If \c VectorSet::value_type is \c std::set, -the return value has size \f$ m \f$ ( \f$ q \f$ ) -and with all its elements between zero and -\f$ q - 1 \f$ ( \f$ m - 1 \f$). - -\par Side Effects -If \c VectorSet::value_type is \c bool, -the forward sparsity pattern for all of the variables on the -tape is stored in \c for_jac_sparse_pack__. -In this case -\verbatim - for_jac_sparse_pack_.n_set() == num_var_tape_ - for_jac_sparse_pack_.end() == q - for_jac_sparse_set_.n_set() == 0 - for_jac_sparse_set_.end() == 0 -\endverbatim -\n -\n -If \c VectorSet::value_type is \c std::set, -the forward sparsity pattern for all of the variables on the -tape is stored in \c for_jac_sparse_set__. -In this case -\verbatim - for_jac_sparse_set_.n_set() == num_var_tape_ - for_jac_sparse_set_.end() == q - for_jac_sparse_pack_.n_set() == 0 - for_jac_sparse_pack_.end() == 0 -\endverbatim -*/ -template -template -VectorSet ADFun::ForSparseJac( - size_t q , - const VectorSet& r , - bool transpose , - bool dependency ) -{ VectorSet s; - typedef typename VectorSet::value_type Set_type; - - // free all memory currently in sparsity patterns - for_jac_sparse_pack_.resize(0, 0); - for_jac_sparse_set_.resize(0, 0); - - ForSparseJacCase( - Set_type() , - transpose , - dependency , - q , - r , - s - ); - - return s; -} -// =========================================================================== -// ForSparseJacCheckpoint -/*! -Forward mode Jacobian sparsity calculation used by checkpoint functions. - -\tparam Base -is the base type for this recording. - -\param transpose -is true (false) s is equal to \f$ S(x) \f$ (\f$ S(x)^T \f$) -where -\f[ - S(x) = F^{(1)} (x) * R -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \f$ x \f$ is any argument value. - -\param q -is the number of columns in the matrix \f$ R \f$. - -\param r -is a sparsity pattern for the matrix \f$ R \f$. - -\param transpose -are the sparsity patterns for \f$ R \f$ and \f$ S(x) \f$ transposed. - -\param dependency -Are the derivatives with respect to left and right of the expression below -considered to be non-zero: -\code - CondExpRel(left, right, if_true, if_false) -\endcode -This is used by the optimizer to obtain the correct dependency relations. - -\param s -The input size and elements of s do not matter. -On output, s is the sparsity pattern for the matrix \f$ S(x) \f$ -or \f$ S(x)^T \f$ depending on transpose. - -\par Side Effects -If \c VectorSet::value_type is \c bool, -the forward sparsity pattern for all of the variables on the -tape is stored in \c for_jac_sparse_pack__. -In this case -\verbatim - for_jac_sparse_pack_.n_set() == num_var_tape_ - for_jac_sparse_pack_.end() == q - for_jac_sparse_set_.n_set() == 0 - for_jac_sparse_set_.end() == 0 -\endverbatim -\n -\n -If \c VectorSet::value_type is \c std::set, -the forward sparsity pattern for all of the variables on the -tape is stored in \c for_jac_sparse_set__. -In this case -\verbatim - for_jac_sparse_set_.n_set() == num_var_tape_ - for_jac_sparse_set_.end() == q - for_jac_sparse_pack_.n_set() == 0 - for_jac_sparse_pack_.end() == 0 -\endverbatim -*/ -template -void ADFun::ForSparseJacCheckpoint( - size_t q , - const local::sparse_list& r , - bool transpose , - bool dependency , - local::sparse_list& s ) -{ size_t n = Domain(); - size_t m = Range(); - -# ifndef NDEBUG - if( transpose ) - { CPPAD_ASSERT_UNKNOWN( r.n_set() == q ); - CPPAD_ASSERT_UNKNOWN( r.end() == n ); - } - else - { CPPAD_ASSERT_UNKNOWN( r.n_set() == n ); - CPPAD_ASSERT_UNKNOWN( r.end() == q ); - } - for(size_t j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] == (j+1) ); - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == local::InvOp ); - } -# endif - - // free all memory currently in sparsity patterns - for_jac_sparse_pack_.resize(0, 0); - for_jac_sparse_set_.resize(0, 0); - - // allocate new sparsity pattern - for_jac_sparse_set_.resize(num_var_tape_, q); - - // set sparsity pattern for dependent variables - if( transpose ) - { for(size_t i = 0; i < q; i++) - { local::sparse_list::const_iterator itr(r, i); - size_t j = *itr; - while( j < n ) - { for_jac_sparse_set_.add_element( ind_taddr_[j], i ); - j = *(++itr); - } - } - } - else - { for(size_t j = 0; j < n; j++) - { local::sparse_list::const_iterator itr(r, j); - size_t i = *itr; - while( i < q ) - { for_jac_sparse_set_.add_element( ind_taddr_[j], i ); - i = *(++itr); - } - } - } - - // evaluate the sparsity pattern for all variables - local::ForJacSweep( - dependency, - n, - num_var_tape_, - &play_, - for_jac_sparse_set_ - ); - - // dimension the return value - if( transpose ) - s.resize(q, m); - else - s.resize(m, q); - - // return values corresponding to dependent variables - for(size_t i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - - // extract the result from for_jac_sparse_set_ - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_set_.end() == q ); - local::sparse_list::const_iterator itr(for_jac_sparse_set_, dep_taddr_[i] ); - size_t j = *itr; - while( j < q ) - { if( transpose ) - s.add_element(j, i); - else - s.add_element(i, j); - j = *(++itr); - } - } - -} - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/for_two.hpp b/ct_core/include/ct/external/cppad/core/for_two.hpp deleted file mode 100644 index cf0734604..000000000 --- a/ct_core/include/ct/external/cppad/core/for_two.hpp +++ /dev/null @@ -1,256 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_FOR_TWO_HPP -# define CPPAD_CORE_FOR_TWO_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin ForTwo$$ -$spell - ddy - typename - Taylor - const -$$ - - - - - -$section Forward Mode Second Partial Derivative Driver$$ -$mindex order easy$$ - -$head Syntax$$ -$icode%ddy% = %f%.ForTwo(%x%, %j%, %k%)%$$ - - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -The syntax above sets -$latex \[ - ddy [ i * p + \ell ] - = - \DD{ F_i }{ x_{j[ \ell ]} }{ x_{k[ \ell ]} } (x) -\] $$ -for $latex i = 0 , \ldots , m-1$$ -and $latex \ell = 0 , \ldots , p$$, -where $latex p$$ is the size of the vectors $icode j$$ and $icode k$$. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/ForTwo Uses Forward/ForTwo/ForTwo Uses Forward/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %VectorBase% &%x% -%$$ -(see $cref/VectorBase/ForTwo/VectorBase/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the partial derivatives listed above. - -$head j$$ -The argument $icode j$$ has prototype -$codei% - const %VectorSize_t% &%j% -%$$ -(see $cref/VectorSize_t/ForTwo/VectorSize_t/$$ below) -We use $icode p$$ to denote the size of the vector $icode j$$. -All of the indices in $icode j$$ -must be less than $icode n$$; i.e., -for $latex \ell = 0 , \ldots , p-1$$, $latex j[ \ell ] < n$$. - -$head k$$ -The argument $icode k$$ has prototype -$codei% - const %VectorSize_t% &%k% -%$$ -(see $cref/VectorSize_t/ForTwo/VectorSize_t/$$ below) -and its size must be equal to $icode p$$, -the size of the vector $icode j$$. -All of the indices in $icode k$$ -must be less than $icode n$$; i.e., -for $latex \ell = 0 , \ldots , p-1$$, $latex k[ \ell ] < n$$. - -$head ddy$$ -The result $icode ddy$$ has prototype -$codei% - %VectorBase% %ddy% -%$$ -(see $cref/VectorBase/ForTwo/VectorBase/$$ below) -and its size is $latex m * p$$. -It contains the requested partial derivatives; to be specific, -for $latex i = 0 , \ldots , m - 1 $$ -and $latex \ell = 0 , \ldots , p - 1$$ -$latex \[ - ddy [ i * p + \ell ] - = - \DD{ F_i }{ x_{j[ \ell ]} }{ x_{k[ \ell ]} } (x) -\] $$ - -$head VectorBase$$ -The type $icode VectorBase$$ must be a $cref SimpleVector$$ class with -$cref/elements of type Base/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head VectorSize_t$$ -The type $icode VectorSize_t$$ must be a $cref SimpleVector$$ class with -$cref/elements of type size_t/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head ForTwo Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to $code ForTwo$$, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0, %x%)%$$ -and the other coefficients are unspecified. - -$head Examples$$ -$children% - example/for_two.cpp -%$$ -The routine -$cref/ForTwo/for_two.cpp/$$ is both an example and test. -It returns $code true$$, if it succeeds and $code false$$ otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -template -VectorBase ADFun::ForTwo( - const VectorBase &x, - const VectorSize_t &j, - const VectorSize_t &k) -{ size_t i; - size_t j1; - size_t k1; - size_t l; - - size_t n = Domain(); - size_t m = Range(); - size_t p = j.size(); - - // check VectorBase is Simple Vector class with Base type elements - CheckSimpleVector(); - - // check VectorSize_t is Simple Vector class with size_t elements - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( - x.size() == n, - "ForTwo: Length of x not equal domain dimension for f." - ); - CPPAD_ASSERT_KNOWN( - j.size() == k.size(), - "ForTwo: Lenght of the j and k vectors are not equal." - ); - // point at which we are evaluating the second partials - Forward(0, x); - - - // dimension the return value - VectorBase ddy(m * p); - - // allocate memory to hold all possible diagonal Taylor coefficients - // (for large sparse cases, this is not efficient) - VectorBase D(m * n); - - // boolean flag for which diagonal coefficients are computed - CppAD::vector c(n); - for(j1 = 0; j1 < n; j1++) - c[j1] = false; - - // direction vector in argument space - VectorBase dx(n); - for(j1 = 0; j1 < n; j1++) - dx[j1] = Base(0); - - // result vector in range space - VectorBase dy(m); - - // compute the diagonal coefficients that are needed - for(l = 0; l < p; l++) - { j1 = j[l]; - k1 = k[l]; - CPPAD_ASSERT_KNOWN( - j1 < n, - "ForTwo: an element of j not less than domain dimension for f." - ); - CPPAD_ASSERT_KNOWN( - k1 < n, - "ForTwo: an element of k not less than domain dimension for f." - ); - size_t count = 2; - while(count) - { count--; - if( ! c[j1] ) - { // diagonal term in j1 direction - c[j1] = true; - dx[j1] = Base(1); - Forward(1, dx); - - dx[j1] = Base(0); - dy = Forward(2, dx); - for(i = 0; i < m; i++) - D[i * n + j1 ] = dy[i]; - } - j1 = k1; - } - } - // compute all the requested cross partials - for(l = 0; l < p; l++) - { j1 = j[l]; - k1 = k[l]; - if( j1 == k1 ) - { for(i = 0; i < m; i++) - ddy[i * p + l] = Base(2) * D[i * n + j1]; - } - else - { - // cross term in j1 and k1 directions - dx[j1] = Base(1); - dx[k1] = Base(1); - Forward(1, dx); - - dx[j1] = Base(0); - dx[k1] = Base(0); - dy = Forward(2, dx); - - // place result in return value - for(i = 0; i < m; i++) - ddy[i * p + l] = dy[i] - D[i*n+j1] - D[i*n+k1]; - - } - } - return ddy; -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/forward.hpp b/ct_core/include/ct/external/cppad/core/forward.hpp deleted file mode 100644 index 8da5ef34d..000000000 --- a/ct_core/include/ct/external/cppad/core/forward.hpp +++ /dev/null @@ -1,425 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_FORWARD_HPP -# define CPPAD_CORE_FORWARD_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// documened after Forward but included here so easy to see -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file forward.hpp -User interface to forward mode computations. -*/ - -/*! -Multiple orders, one direction, forward mode Taylor coefficieints. - -\tparam Base -The type used during the forward mode computations; i.e., the corresponding -recording of operations used the type AD. - -\tparam VectorBase -is a Simple Vector class with eleements of type Base. - -\param q -is the hightest order for this forward mode computation; i.e., -after this calculation there will be q+1 -Taylor coefficients per variable. - -\param xq -contains Taylor coefficients for the independent variables. -The size of xq must either be n or (q+1)*n, -We define p = q + 1 - xq.size()/n. -For j = 0 , ... , n-1, -k = p, ... , q, are -xq[ (q+1-p)*j + k - p ] -is the k-th order coefficient for the j-th independent variable. - -\param s -Is the stream where output corresponding to PriOp operations will written. - -\return -contains Taylor coefficients for the dependent variables. -The size of the return value y is m*(q+1-p). -For i = 0, ... , m-1, -k = p, ..., q, -y[(q+1-p)*i + (k-p)] -is the k-th order coefficient for the i-th dependent variable. - -\par taylor_ -The Taylor coefficients up to order p-1 are inputs -and the coefficents from order p through q are outputs. -Let N = num_var_tape_, and -C = cap_order_taylor_. -Note that for -i = 1 , ..., N-1, -k = 0 , ..., q, -taylor_[ C*i + k ] -is the k-th order cofficent, -for the i-th varaible on the tape. -(The first independent variable has index one on the tape -and there is no variable with index zero.) -*/ - -template -template -VectorBase ADFun::Forward( - size_t q , - const VectorBase& xq , - std::ostream& s ) -{ // temporary indices - size_t i, j, k; - - // number of independent variables - size_t n = ind_taddr_.size(); - - // number of dependent variables - size_t m = dep_taddr_.size(); - - // check Vector is Simple Vector class with Base type elements - CheckSimpleVector(); - - - CPPAD_ASSERT_KNOWN( - size_t(xq.size()) == n || size_t(xq.size()) == n*(q+1), - "Forward(q, xq): xq.size() is not equal n or n*(q+1)" - ); - - // lowest order we are computing - size_t p = q + 1 - size_t(xq.size()) / n; - CPPAD_ASSERT_UNKNOWN( p == 0 || p == q ); - CPPAD_ASSERT_KNOWN( - q <= num_order_taylor_ || p == 0, - "Forward(q, xq): Number of Taylor coefficient orders stored in this" - " ADFun\nis less than q and xq.size() != n*(q+1)." - ); - CPPAD_ASSERT_KNOWN( - p <= 1 || num_direction_taylor_ == 1, - "Forward(q, xq): computing order q >= 2" - " and number of directions is not one." - "\nMust use Forward(q, r, xq) for this case" - ); - // does taylor_ need more orders or fewer directions - if( (cap_order_taylor_ <= q) | (num_direction_taylor_ != 1) ) - { if( p == 0 ) - { // no need to copy old values during capacity_order - num_order_taylor_ = 0; - } - else num_order_taylor_ = q; - size_t c = std::max(q + 1, cap_order_taylor_); - size_t r = 1; - capacity_order(c, r); - } - CPPAD_ASSERT_UNKNOWN( cap_order_taylor_ > q ); - CPPAD_ASSERT_UNKNOWN( num_direction_taylor_ == 1 ); - - // short hand notation for order capacity - size_t C = cap_order_taylor_; - - // set Taylor coefficients for independent variables - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] < num_var_tape_ ); - - // ind_taddr_[j] is operator taddr for j-th independent variable - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == local::InvOp ); - - if( p == q ) - taylor_[ C * ind_taddr_[j] + q] = xq[j]; - else - { for(k = 0; k <= q; k++) - taylor_[ C * ind_taddr_[j] + k] = xq[ (q+1)*j + k]; - } - } - - // evaluate the derivatives - CPPAD_ASSERT_UNKNOWN( cskip_op_.size() == play_.num_op_rec() ); - CPPAD_ASSERT_UNKNOWN( load_op_.size() == play_.num_load_op_rec() ); - if( q == 0 ) - { local::forward0sweep(s, true, - n, num_var_tape_, &play_, C, - taylor_.data(), cskip_op_.data(), load_op_, - compare_change_count_, - compare_change_number_, - compare_change_op_index_ - ); - } - else - { local::forward1sweep(s, true, p, q, - n, num_var_tape_, &play_, C, - taylor_.data(), cskip_op_.data(), load_op_, - compare_change_count_, - compare_change_number_, - compare_change_op_index_ - ); - } - - // return Taylor coefficients for dependent variables - VectorBase yq; - if( p == q ) - { yq.resize(m); - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - yq[i] = taylor_[ C * dep_taddr_[i] + q]; - } - } - else - { yq.resize(m * (q+1) ); - for(i = 0; i < m; i++) - { for(k = 0; k <= q; k++) - yq[ (q+1) * i + k] = - taylor_[ C * dep_taddr_[i] + k ]; - } - } -# ifndef NDEBUG - if( check_for_nan_ ) - { bool ok = true; - size_t index = m; - if( p == 0 ) - { for(i = 0; i < m; i++) - { // Visual Studio 2012, CppAD required in front of isnan ? - if( CppAD::isnan( yq[ (q+1) * i + 0 ] ) ) - { ok = false; - if( index == m ) - index = i; - } - } - } - if( ! ok ) - { CPPAD_ASSERT_UNKNOWN( index < m ); - // - CppAD::vector x0(n); - for(j = 0; j < n; j++) - x0[j] = taylor_[ C * ind_taddr_[j] + 0 ]; - std::string file_name; - put_check_for_nan(x0, file_name); - std::stringstream ss; - ss << - "yq = f.Forward(q, xq): a zero order Taylor coefficient is nan.\n" - "Corresponding independent variables vector was written " - "to binary a file.\n" - "vector_size = " << n << "\n" << - "file_name = " << file_name << "\n" << - "index = " << index << "\n"; - // ss.str() returns a string object with a copy of the current - // contents in the stream buffer. - std::string msg_str = ss.str(); - // msg_str.c_str() returns a pointer to the c-string - // representation of the string object's value. - const char* msg_char_star = msg_str.c_str(); - ErrorHandler::Call( - true, - __LINE__, - __FILE__, - "if( CppAD::isnan( yq[ (q+1) * index + 0 ] )", - msg_char_star - ); - } - CPPAD_ASSERT_KNOWN(ok, - "with the value nan." - ); - if( 0 < q ) - { for(i = 0; i < m; i++) - { for(k = p; k <= q; k++) - { // Studio 2012, CppAD required in front of isnan ? - ok &= ! CppAD::isnan( yq[ (q+1-p)*i + k-p ] ); - } - } - } - CPPAD_ASSERT_KNOWN(ok, - "yq = f.Forward(q, xq): has a non-zero order Taylor coefficient\n" - "with the value nan (but zero order coefficients are not nan)." - ); - } -# endif - - // now we have q + 1 taylor_ coefficient orders per variable - num_order_taylor_ = q + 1; - - return yq; -} - -/*! -One order, multiple directions, forward mode Taylor coefficieints. - -\tparam Base -The type used during the forward mode computations; i.e., the corresponding -recording of operations used the type AD. - -\tparam VectorBase -is a Simple Vector class with eleements of type Base. - -\param q -is the order for this forward mode computation, -q > 0. -There must be at least q Taylor coefficients -per variable before this call. -After this call there will be q+1 -Taylor coefficients per variable. - -\param r -is the number of directions for this calculation. -If q != 1, \c r must be the same as in the previous -call to Forward where \c q was equal to one. - -\param xq -contains Taylor coefficients for the independent variables. -The size of xq must either be r*n, -For j = 0 , ... , n-1, -ell = 0, ... , r-1, -xq[ ( r*j + ell ] -is the q-th order coefficient for the j-th independent variable -and the ell-th direction. - -\return -contains Taylor coefficients for the dependent variables. -The size of the return value \c y is r*m. -For i = 0, ... , m-1, -ell = 0, ... , r-1, -y[ r*i + ell ] -is the q-th order coefficient for the i-th dependent variable -and the ell-th direction. - -\par taylor_ -The Taylor coefficients up to order q-1 are inputs -and the coefficents of order \c q are outputs. -Let N = num_var_tape_, and -C = cap_order_taylor_. -Note that for -i = 1 , ..., N-1, -taylor_[ (C-1)*r*i + i + 0 ] -is the zero order cofficent, -for the i-th varaible, and all directions. -For i = 1 , ..., N-1, -k = 1 , ..., q, -ell = 0 , ..., r-1, -taylor_[ (C-1)*r*i + i + (k-1)*r + ell + 1 ] -is the k-th order cofficent, -for the i-th varaible, and ell-th direction. -(The first independent variable has index one on the tape -and there is no variable with index zero.) -*/ - -template -template -VectorBase ADFun::Forward( - size_t q , - size_t r , - const VectorBase& xq ) -{ // temporary indices - size_t i, j, ell; - - // number of independent variables - size_t n = ind_taddr_.size(); - - // number of dependent variables - size_t m = dep_taddr_.size(); - - // check Vector is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( q > 0, "Forward(q, r, xq): q == 0" ); - CPPAD_ASSERT_KNOWN( - size_t(xq.size()) == r * n, - "Forward(q, r, xq): xq.size() is not equal r * n" - ); - CPPAD_ASSERT_KNOWN( - q <= num_order_taylor_ , - "Forward(q, r, xq): Number of Taylor coefficient orders stored in" - " this ADFun is less than q" - ); - CPPAD_ASSERT_KNOWN( - q == 1 || num_direction_taylor_ == r , - "Forward(q, r, xq): q > 1 and number of Taylor directions r" - " is not same as previous Forward(1, r, xq)" - ); - - // does taylor_ need more orders or new number of directions - if( cap_order_taylor_ <= q || num_direction_taylor_ != r ) - { if( num_direction_taylor_ != r ) - num_order_taylor_ = 1; - - size_t c = std::max(q + 1, cap_order_taylor_); - capacity_order(c, r); - } - CPPAD_ASSERT_UNKNOWN( cap_order_taylor_ > q ); - CPPAD_ASSERT_UNKNOWN( num_direction_taylor_ == r ) - - // short hand notation for order capacity - size_t c = cap_order_taylor_; - - // set Taylor coefficients for independent variables - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] < num_var_tape_ ); - - // ind_taddr_[j] is operator taddr for j-th independent variable - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == local::InvOp ); - - for(ell = 0; ell < r; ell++) - { size_t index = ((c-1)*r + 1)*ind_taddr_[j] + (q-1)*r + ell + 1; - taylor_[ index ] = xq[ r * j + ell ]; - } - } - - // evaluate the derivatives - CPPAD_ASSERT_UNKNOWN( cskip_op_.size() == play_.num_op_rec() ); - CPPAD_ASSERT_UNKNOWN( load_op_.size() == play_.num_load_op_rec() ); - local::forward2sweep( - q, - r, - n, - num_var_tape_, - &play_, - c, - taylor_.data(), - cskip_op_.data(), - load_op_ - ); - - // return Taylor coefficients for dependent variables - VectorBase yq; - yq.resize(r * m); - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - for(ell = 0; ell < r; ell++) - { size_t index = ((c-1)*r + 1)*dep_taddr_[i] + (q-1)*r + ell + 1; - yq[ r * i + ell ] = taylor_[ index ]; - } - } -# ifndef NDEBUG - if( check_for_nan_ ) - { bool ok = true; - for(i = 0; i < m; i++) - { for(ell = 0; ell < r; ell++) - { // Studio 2012, CppAD required in front of isnan ? - ok &= ! CppAD::isnan( yq[ r * i + ell ] ); - } - } - CPPAD_ASSERT_KNOWN(ok, - "yq = f.Forward(q, r, xq): has a non-zero order Taylor coefficient\n" - "with the value nan (but zero order coefficients are not nan)." - ); - } -# endif - - // now we have q + 1 taylor_ coefficient orders per variable - num_order_taylor_ = q + 1; - - return yq; -} - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/fun_check.hpp b/ct_core/include/ct/external/cppad/core/fun_check.hpp deleted file mode 100644 index 432ece131..000000000 --- a/ct_core/include/ct/external/cppad/core/fun_check.hpp +++ /dev/null @@ -1,211 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_FUN_CHECK_HPP -# define CPPAD_CORE_FUN_CHECK_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin FunCheck$$ -$spell - exp - bool - const - Taylor -$$ - - -$section Check an ADFun Sequence of Operations$$ - -$head Syntax$$ -$icode%ok% = FunCheck(%f%, %g%, %x%, %r%, %a%)%$$ -$pre -$$ -$bold See Also$$ -$cref CompareChange$$ - - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -We use $latex G : B^n \rightarrow B^m$$ to denote the -function corresponding to the C++ function object $icode g$$. -This routine check if -$latex \[ - F(x) = G(x) -\]$$ -If $latex F(x) \neq G(x)$$, the -$cref/operation sequence/glossary/Operation/Sequence/$$ -corresponding to $icode f$$ does not represents the algorithm used -by $icode g$$ to calculate values for $latex G$$ -(see $cref/Discussion/FunCheck/Discussion/$$ below). - -$head f$$ -The $code FunCheck$$ argument $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/Forward/FunCheck/FunCheck Uses Forward/$$ below). - -$head g$$ -The $code FunCheck$$ argument $icode g$$ has prototype -$codei% - %Fun% &%g% -%$$ -($icode Fun$$ is defined the properties of $icode g$$). -The C++ function object $icode g$$ supports the syntax -$codei% - %y% = %g%(%x%) -%$$ -which computes $latex y = G(x)$$. - -$subhead x$$ -The $icode g$$ argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -(see $cref/Vector/FunCheck/Vector/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. - -$head y$$ -The $icode g$$ result $icode y$$ has prototype -$codei% - %Vector% %y% -%$$ -and its value is $latex G(x)$$. -The size of $icode y$$ -is equal to $icode m$$, the dimension of the -$cref/range/seq_property/Range/$$ space for $icode f$$. - -$head x$$ -The $code FunCheck$$ argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -This specifies that point at which to compare the values -calculated by $icode f$$ and $icode G$$. - -$head r$$ -The $code FunCheck$$ argument $icode r$$ has prototype -$codei% - const %Base% &%r% -%$$ -It specifies the relative error the element by element -comparison of the value of $latex F(x)$$ and $latex G(x)$$. - -$head a$$ -The $code FunCheck$$ argument $icode a$$ has prototype -$codei% - const %Base% &%a% -%$$ -It specifies the absolute error the element by element -comparison of the value of $latex F(x)$$ and $latex G(x)$$. - -$head ok$$ -The $code FunCheck$$ result $icode ok$$ has prototype -$codei% - bool %ok% -%$$ -It is true, if for $latex i = 0 , \ldots , m-1$$ -either the relative error bound is satisfied -$latex \[ -| F_i (x) - G_i (x) | -\leq -r ( | F_i (x) | + | G_i (x) | ) -\] $$ -or the absolute error bound is satisfied -$latex \[ - | F_i (x) - G_i (x) | \leq a -\] $$ -It is false if for some $latex (i, j)$$ neither -of these bounds is satisfied. - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Base$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head FunCheck Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After $code FunCheck$$, -the previous calls to $cref Forward$$ are undefined. - -$head Discussion$$ -Suppose that the algorithm corresponding to $icode g$$ contains -$codei% - if( %x% >= 0 ) - %y% = exp(%x%) - else %y% = exp(-%x%) -%$$ -where $icode x$$ and $icode y$$ are $codei%AD%$$ objects. -It follows that the -AD of $code double$$ $cref/operation sequence/glossary/Operation/Sequence/$$ -depends on the value of $icode x$$. -If the sequence of operations stored in $icode f$$ corresponds to -$icode g$$ with $latex x \geq 0$$, -the function values computed using $icode f$$ when $latex x < 0$$ -will not agree with the function values computed by $latex g$$. -This is because the operation sequence corresponding to $icode g$$ changed -(and hence the object $icode f$$ does not represent the function -$latex G$$ for this value of $icode x$$). -In this case, you probably want to re-tape the calculations -performed by $icode g$$ with the -$cref/independent variables/glossary/Tape/Independent Variable/$$ -equal to the values in $icode x$$ -(so AD operation sequence properly represents the algorithm -for this value of independent variables). - - -$head Example$$ -$children% - example/fun_check.cpp -%$$ -The file -$cref fun_check.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end ---------------------------------------------------------------------------- -*/ - -namespace CppAD { - template - bool FunCheck( - ADFun &f , - Fun &g , - const Vector &x , - const Base &r , - const Base &a ) - { bool ok = true; - - size_t m = f.Range(); - Vector yf = f.Forward(0, x); - Vector yg = g(x); - - size_t i; - for(i = 0; i < m; i++) - ok &= NearEqual(yf[i], yg[i], r, a); - return ok; - } -} - -# endif diff --git a/ct_core/include/ct/external/cppad/core/fun_construct.hpp b/ct_core/include/ct/external/cppad/core/fun_construct.hpp deleted file mode 100644 index 29b9768bc..000000000 --- a/ct_core/include/ct/external/cppad/core/fun_construct.hpp +++ /dev/null @@ -1,489 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_FUN_CONSTRUCT_HPP -# define CPPAD_CORE_FUN_CONSTRUCT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin FunConstruct$$ -$spell - alloc - num - Jac - bool - taylor - var - ADvector - const - Jacobian -$$ - -$spell -$$ - -$section Construct an ADFun Object and Stop Recording$$ -$mindex tape$$ - - -$head Syntax$$ -$codei%ADFun<%Base%> %f%, %g% -%$$ -$codei%ADFun<%Base%> %f%(%x%, %y%) -%$$ -$icode%g% = %f% -%$$ - - -$head Purpose$$ -The $codei%AD<%Base%>%$$ object $icode f$$ can -store an AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. -It can then be used to calculate derivatives of the corresponding -$cref/AD function/glossary/AD Function/$$ -$latex \[ - F : B^n \rightarrow B^m -\] $$ -where $latex B$$ is the space corresponding to objects of type $icode Base$$. - -$head x$$ -If the argument $icode x$$ is present, it has prototype -$codei% - const %VectorAD% &%x% -%$$ -It must be the vector argument in the previous call to -$cref Independent$$. -Neither its size, or any of its values, are allowed to change -between calling -$codei% - Independent(%x%) -%$$ -and -$codei% - ADFun<%Base%> %f%(%x%, %y%) -%$$ - -$head y$$ -If the argument $icode y$$ is present, it has prototype -$codei% - const %VectorAD% &%y% -%$$ -The sequence of operations that map $icode x$$ -to $icode y$$ are stored in the ADFun object $icode f$$. - -$head VectorAD$$ -The type $icode VectorAD$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$codei%AD<%Base%>%$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Default Constructor$$ -The default constructor -$codei% - ADFun<%Base%> %f% -%$$ -creates an -$codei%AD<%Base%>%$$ object with no corresponding operation sequence; i.e., -$codei% - %f%.size_var() -%$$ -returns the value zero (see $cref/size_var/seq_property/size_var/$$). - -$head Sequence Constructor$$ -The sequence constructor -$codei% - ADFun<%Base%> %f%(%x%, %y%) -%$$ -creates the $codei%AD<%Base%>%$$ object $icode f$$, -stops the recording of AD of $icode Base$$ operations -corresponding to the call -$codei% - Independent(%x%) -%$$ -and stores the corresponding operation sequence in the object $icode f$$. -It then stores the zero order Taylor coefficients -(corresponding to the value of $icode x$$) in $icode f$$. -This is equivalent to the following steps using the default constructor: - -$list number$$ -Create $icode f$$ with the default constructor -$codei% - ADFun<%Base%> %f%; -%$$ -$lnext -Stop the tape and storing the operation sequence using -$codei% - %f%.Dependent(%x%, %y%); -%$$ -(see $cref Dependent$$). -$lnext -Calculate the zero order Taylor coefficients for all -the variables in the operation sequence using -$codei% - %f%.Forward(%p%, %x_p%) -%$$ -with $icode p$$ equal to zero and the elements of $icode x_p$$ -equal to the corresponding elements of $icode x$$ -(see $cref Forward$$). -$lend - -$head Copy Constructor$$ -It is an error to attempt to use the $codei%ADFun<%Base%>%$$ copy constructor; -i.e., the following syntax is not allowed: -$codei% - ADFun<%Base%> %g%(%f%) -%$$ -where $icode f$$ is an $codei%ADFun<%Base%>%$$ object. -Use its $cref/default constructor/FunConstruct/Default Constructor/$$ instead -and its assignment operator. - -$head Assignment Operator$$ -The $codei%ADFun<%Base%>%$$ assignment operation -$codei% - %g% = %f% -%$$ -makes a copy of the operation sequence currently stored in $icode f$$ -in the object $icode g$$. -The object $icode f$$ is not affected by this operation and -can be $code const$$. -All of information (state) stored in $icode f$$ is copied to $icode g$$ -and any information originally in $icode g$$ is lost. - -$subhead Taylor Coefficients$$ -The Taylor coefficient information currently stored in $icode f$$ -(computed by $cref/f.Forward/Forward/$$) is -copied to $icode g$$. -Hence, directly after this operation -$codei% - %g%.size_order() == %f%.size_order() -%$$ - -$subhead Sparsity Patterns$$ -The forward Jacobian sparsity pattern currently stored in $icode f$$ -(computed by $cref/f.ForSparseJac/ForSparseJac/$$) is -copied to $icode g$$. -Hence, directly after this operation -$codei% - %g%.size_forward_bool() == %f%.size_forward_bool() - %g%.size_forward_set() == %f%.size_forward_set() -%$$ - -$head Parallel Mode$$ -The call to $code Independent$$, -and the corresponding call to -$codei% - ADFun<%Base%> %f%( %x%, %y%) -%$$ -or -$codei% - %f%.Dependent( %x%, %y%) -%$$ -or $cref abort_recording$$, -must be preformed by the same thread; i.e., -$cref/thread_alloc::thread_num/ta_thread_num/$$ must be the same. - -$head Example$$ - -$subhead Sequence Constructor$$ -The file -$cref independent.cpp$$ -contains an example and test of the sequence constructor. -It returns true if it succeeds and false otherwise. - -$subhead Default Constructor$$ -The files -$cref fun_check.cpp$$ -and -$cref hes_lagrangian.cpp$$ -contain an examples and tests using the default constructor. -They return true if they succeed and false otherwise. - -$children% - example/fun_assign.cpp -%$$ -$subhead Assignment Operator$$ -The file -$cref fun_assign.cpp$$ -contains an example and test of the $codei%ADFun<%Base%>%$$ -assignment operator. -It returns true if it succeeds and false otherwise. - -$end ----------------------------------------------------------------------------- -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file fun_construct.hpp -ADFun function constructors and assignment operator. -*/ - -/*! -ADFun default constructor - -The C++ syntax for this operation is -\verbatim - ADFun f -\endverbatim -An empty ADFun object is created. -The Dependent member function, -or the ADFun assingment operator, -can then be used to put an operation sequence in this ADFun object. - -\tparam Base -is the base for the recording that can be stored in this ADFun object; -i.e., operation sequences that were recorded using the type \c AD. -*/ -template -ADFun::ADFun(void) : -has_been_optimized_(false), -check_for_nan_(true) , -compare_change_count_(1), -compare_change_number_(0), -compare_change_op_index_(0), -num_var_tape_(0) -{ } - -/*! -ADFun assignment operator - -The C++ syntax for this operation is -\verbatim - g = f -\endverbatim -where \c g and \c f are ADFun ADFun objects. -A copy of the the operation sequence currently stored in \c f -is placed in this ADFun object (called \c g above). -Any information currently stored in this ADFun object is lost. - -\tparam Base -is the base for the recording that can be stored in this ADFun object; -i.e., operation sequences that were recorded using the type \c AD. - -\param f -ADFun object containing the operation sequence to be copied. -*/ -template -void ADFun::operator=(const ADFun& f) -{ size_t m = f.Range(); - size_t n = f.Domain(); - size_t i; - - // go through member variables in ad_fun.hpp order - // - // size_t objects - has_been_optimized_ = f.has_been_optimized_; - check_for_nan_ = f.check_for_nan_; - compare_change_count_ = f.compare_change_count_; - compare_change_number_ = f.compare_change_number_; - compare_change_op_index_ = f.compare_change_op_index_; - num_order_taylor_ = f.num_order_taylor_; - cap_order_taylor_ = f.cap_order_taylor_; - num_direction_taylor_ = f.num_direction_taylor_; - num_var_tape_ = f.num_var_tape_; - // - // CppAD::vector objects - ind_taddr_.resize(n); - ind_taddr_ = f.ind_taddr_; - dep_taddr_.resize(m); - dep_taddr_ = f.dep_taddr_; - dep_parameter_.resize(m); - dep_parameter_ = f.dep_parameter_; - // - // pod_vector objects - taylor_ = f.taylor_; - cskip_op_ = f.cskip_op_; - load_op_ = f.load_op_; - // - // player - play_ = f.play_; - // - // sparse_pack - for_jac_sparse_pack_.resize(0, 0); - size_t n_set = f.for_jac_sparse_pack_.n_set(); - size_t end = f.for_jac_sparse_pack_.end(); - if( n_set > 0 ) - { CPPAD_ASSERT_UNKNOWN( n_set == num_var_tape_ ); - CPPAD_ASSERT_UNKNOWN( f.for_jac_sparse_set_.n_set() == 0 ); - for_jac_sparse_pack_.resize(n_set, end); - for(i = 0; i < num_var_tape_ ; i++) - { for_jac_sparse_pack_.assignment( - i , - i , - f.for_jac_sparse_pack_ - ); - } - } - // - // sparse_set - for_jac_sparse_set_.resize(0, 0); - n_set = f.for_jac_sparse_set_.n_set(); - end = f.for_jac_sparse_set_.end(); - if( n_set > 0 ) - { CPPAD_ASSERT_UNKNOWN( n_set == num_var_tape_ ); - CPPAD_ASSERT_UNKNOWN( f.for_jac_sparse_pack_.n_set() == 0 ); - for_jac_sparse_set_.resize(n_set, end); - for(i = 0; i < num_var_tape_; i++) - { for_jac_sparse_set_.assignment( - i , - i , - f.for_jac_sparse_set_ - ); - } - } -} - -/*! -ADFun constructor from an operation sequence. - -The C++ syntax for this operation is -\verbatim - ADFun f(x, y) -\endverbatim -The operation sequence that started with the previous call -\c Independent(x), and that ends with this operation, is stored -in this \c ADFun object \c f. - -\tparam Base -is the base for the recording that will be stored in the object \c f; -i.e., the operations were recorded using the type \c AD. - -\tparam VectorAD -is a simple vector class with elements of typea \c AD. - -\param x -is the independent variable vector for this ADFun object. -The domain dimension of this object will be the size of \a x. - -\param y -is the dependent variable vector for this ADFun object. -The range dimension of this object will be the size of \a y. - -\par Taylor Coefficients -A zero order forward mode sweep is done, -and if NDEBUG is not defined the resulting values for the -depenedent variables are checked against the values in \a y. -Thus, the zero order Taylor coefficients -corresponding to the value of the \a x vector -are stored in this ADFun object. -*/ -template -template -ADFun::ADFun(const VectorAD &x, const VectorAD &y) -{ - CPPAD_ASSERT_KNOWN( - x.size() > 0, - "ADFun: independent variable vector has size zero." - ); - CPPAD_ASSERT_KNOWN( - Variable(x[0]), - "ADFun: independent variable vector has been changed." - ); - local::ADTape* tape = AD::tape_ptr(x[0].tape_id_); - CPPAD_ASSERT_KNOWN( - tape->size_independent_ == size_t ( x.size() ), - "ADFun: independent variable vector has been changed." - ); - size_t j, n = x.size(); -# ifndef NDEBUG - size_t i, m = y.size(); - for(j = 0; j < n; j++) - { CPPAD_ASSERT_KNOWN( - size_t(x[j].taddr_) == (j+1), - "ADFun: independent variable vector has been changed." - ); - CPPAD_ASSERT_KNOWN( - x[j].tape_id_ == x[0].tape_id_, - "ADFun: independent variable vector has been changed." - ); - } - for(i = 0; i < m; i++) - { CPPAD_ASSERT_KNOWN( - CppAD::Parameter( y[i] ) | (y[i].tape_id_ == x[0].tape_id_) , - "ADFun: dependent vector contains variables for" - "\na different tape than the independent variables." - ); - } -# endif - - // stop the tape and store the operation sequence - Dependent(tape, y); - - - // ad_fun.hpp member values not set by dependent - check_for_nan_ = true; - - // allocate memory for one zero order taylor_ coefficient - CPPAD_ASSERT_UNKNOWN( num_order_taylor_ == 0 ); - CPPAD_ASSERT_UNKNOWN( num_direction_taylor_ == 0 ); - size_t c = 1; - size_t r = 1; - capacity_order(c, r); - CPPAD_ASSERT_UNKNOWN( cap_order_taylor_ == c ); - CPPAD_ASSERT_UNKNOWN( num_direction_taylor_ == r ); - - // set zero order coefficients corresponding to indpendent variables - CPPAD_ASSERT_UNKNOWN( n == ind_taddr_.size() ); - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] == (j+1) ); - CPPAD_ASSERT_UNKNOWN( size_t(x[j].taddr_) == (j+1) ); - taylor_[ ind_taddr_[j] ] = x[j].value_; - } - - // use independent variable values to fill in values for others - CPPAD_ASSERT_UNKNOWN( cskip_op_.size() == play_.num_op_rec() ); - CPPAD_ASSERT_UNKNOWN( load_op_.size() == play_.num_load_op_rec() ); - local::forward0sweep(std::cout, false, - n, num_var_tape_, &play_, cap_order_taylor_, taylor_.data(), - cskip_op_.data(), load_op_, - compare_change_count_, - compare_change_number_, - compare_change_op_index_ - ); - CPPAD_ASSERT_UNKNOWN( compare_change_count_ == 1 ); - CPPAD_ASSERT_UNKNOWN( compare_change_number_ == 0 ); - CPPAD_ASSERT_UNKNOWN( compare_change_op_index_ == 0 ); - - // now set the number of orders stored - num_order_taylor_ = 1; - -# ifndef NDEBUG - // on MS Visual Studio 2012, CppAD required in front of isnan ? - for(i = 0; i < m; i++) - if( taylor_[dep_taddr_[i]] != y[i].value_ || CppAD::isnan( y[i].value_ ) ) - { using std::endl; - std::ostringstream buf; - buf << "A dependent variable value is not equal to " - << "its tape evaluation value," << endl - << "perhaps it is nan." << endl - << "Dependent variable value = " - << y[i].value_ << endl - << "Tape evaluation value = " - << taylor_[dep_taddr_[i]] << endl - << "Difference = " - << y[i].value_ - taylor_[dep_taddr_[i]] << endl - ; - // buf.str() returns a string object with a copy of the current - // contents in the stream buffer. - std::string msg_str = buf.str(); - // msg_str.c_str() returns a pointer to the c-string - // representation of the string object's value. - const char* msg_char_star = msg_str.c_str(); - CPPAD_ASSERT_KNOWN( - 0, - msg_char_star - ); - } -# endif -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/fun_eval.hpp b/ct_core/include/ct/external/cppad/core/fun_eval.hpp deleted file mode 100644 index 827545ff8..000000000 --- a/ct_core/include/ct/external/cppad/core/fun_eval.hpp +++ /dev/null @@ -1,37 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_FUN_EVAL_HPP -# define CPPAD_CORE_FUN_EVAL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin FunEval$$ -$spell -$$ - - -$section Evaluate ADFun Functions, Derivatives, and Sparsity Patterns$$ - -$childtable% - omh/forward/forward.omh% - omh/reverse/reverse.omh% - cppad/core/sparse.hpp -%$$ - -$end -*/ - -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/core/hash_code.hpp b/ct_core/include/ct/external/cppad/core/hash_code.hpp deleted file mode 100644 index a067b265f..000000000 --- a/ct_core/include/ct/external/cppad/core/hash_code.hpp +++ /dev/null @@ -1,51 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_HASH_CODE_HPP -# define CPPAD_CORE_HASH_CODE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/*! -\file core/hash_code.hpp -CppAD hashing utility. -*/ -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -General purpose hash code for an arbitrary value. - -\tparam Value -is the type of the argument being hash coded. -It should be a plain old data class; i.e., -the values included in the equality operator in the object and -not pointed to by the object. - -\param value -the value that we are generating a hash code for. -All of the fields in value should have been set before the hash code -is computed (otherwise undefined values are used). - -\return -is a hash code that is between zero and CPPAD_HASH_TABLE_SIZE - 1. - -\par Checked Assertions -\li \c std::numeric_limits::max() >= CPPAD_HASH_TABLE_SIZE -\li \c sizeof(value) is even -\li \c sizeof(unsigned short) == 2 -*/ -template -unsigned short hash_code(const Value& value) -{ return local::local_hash_code(value); } - -} // END_CPPAD_NAMESPACE - - -# endif diff --git a/ct_core/include/ct/external/cppad/core/hessian.hpp b/ct_core/include/ct/external/cppad/core/hessian.hpp deleted file mode 100644 index 1c673c8a5..000000000 --- a/ct_core/include/ct/external/cppad/core/hessian.hpp +++ /dev/null @@ -1,215 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_HESSIAN_HPP -# define CPPAD_CORE_HESSIAN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Hessian$$ -$spell - hes - typename - Taylor - HesLuDet - const -$$ - - -$section Hessian: Easy Driver$$ -$mindex second derivative$$ - -$head Syntax$$ -$icode%hes% = %f%.Hessian(%x%, %w%) -%$$ -$icode%hes% = %f%.Hessian(%x%, %l%) -%$$ - - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -The syntax above sets $icode hes$$ to the Hessian -The syntax above sets $icode h$$ to the Hessian -$latex \[ - hes = \dpow{2}{x} \sum_{i=1}^m w_i F_i (x) -\] $$ -The routine $cref sparse_hessian$$ may be faster in the case -where the Hessian is sparse. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/Hessian Uses Forward/Hessian/Hessian Uses Forward/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -(see $cref/Vector/Hessian/Vector/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the Hessian. - -$head l$$ -If the argument $icode l$$ is present, it has prototype -$codei% - size_t %l% -%$$ -and is less than $icode m$$, the dimension of the -$cref/range/seq_property/Range/$$ space for $icode f$$. -It specifies the component of $icode F$$ -for which we are evaluating the Hessian. -To be specific, in the case where the argument $icode l$$ is present, -$latex \[ - w_i = \left\{ \begin{array}{ll} - 1 & i = l \\ - 0 & {\rm otherwise} - \end{array} \right. -\] $$ - -$head w$$ -If the argument $icode w$$ is present, it has prototype -$codei% - const %Vector% &%w% -%$$ -and size $latex m$$. -It specifies the value of $latex w_i$$ in the expression -for $icode h$$. - -$head hes$$ -The result $icode hes$$ has prototype -$codei% - %Vector% %hes% -%$$ -(see $cref/Vector/Hessian/Vector/$$ below) -and its size is $latex n * n$$. -For $latex j = 0 , \ldots , n - 1 $$ -and $latex \ell = 0 , \ldots , n - 1$$ -$latex \[ - hes [ j * n + \ell ] = \DD{ w^{\rm T} F }{ x_j }{ x_\ell } ( x ) -\] $$ - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Base$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Hessian Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to $code Hessian$$, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0, %x%)%$$ -and the other coefficients are unspecified. - -$head Example$$ -$children% - example/hessian.cpp% - example/hes_lagrangian.cpp -%$$ -The routines -$cref hessian.cpp$$ and -$cref hes_lagrangian.cpp$$ -are examples and tests of $code Hessian$$. -They return $code true$$, if they succeed and $code false$$ otherwise. - - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -template -Vector ADFun::Hessian(const Vector &x, size_t l) -{ size_t i, m = Range(); - CPPAD_ASSERT_KNOWN( - l < m, - "Hessian: index i is not less than range dimension for f" - ); - - Vector w(m); - for(i = 0; i < m; i++) - w[i] = Base(0); - w[l] = Base(1); - - return Hessian(x, w); -} - - -template -template -Vector ADFun::Hessian(const Vector &x, const Vector &w) -{ size_t j; - size_t k; - - size_t n = Domain(); - - // check Vector is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( - size_t(x.size()) == n, - "Hessian: length of x not equal domain dimension for f" - ); - CPPAD_ASSERT_KNOWN( - size_t(w.size()) == Range(), - "Hessian: length of w not equal range dimension for f" - ); - - // point at which we are evaluating the Hessian - Forward(0, x); - - // define the return value - Vector hes(n * n); - - // direction vector for calls to forward - Vector u(n); - for(j = 0; j < n; j++) - u[j] = Base(0); - - - // location for return values from Reverse - Vector ddw(n * 2); - - // loop over forward directions - for(j = 0; j < n; j++) - { // evaluate partials of entire function w.r.t. j-th coordinate - u[j] = Base(1); - Forward(1, u); - u[j] = Base(0); - - // evaluate derivative of partial corresponding to F_i - ddw = Reverse(2, w); - - // return desired components - for(k = 0; k < n; k++) - hes[k * n + j] = ddw[k * 2 + 1]; - } - - return hes; -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/identical.hpp b/ct_core/include/ct/external/cppad/core/identical.hpp deleted file mode 100644 index 31ed8ea55..000000000 --- a/ct_core/include/ct/external/cppad/core/identical.hpp +++ /dev/null @@ -1,105 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_IDENTICAL_HPP -# define CPPAD_CORE_IDENTICAL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-17 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file identical.hpp -Check if certain properties is true for any possible AD tape play back. -*/ - -// --------------------------------------------------------------------------- -/*! -Determine if an AD object is a parameter, and could never have -a different value during any tape playback. - -An AD object \c x is identically a parameter if and only if -all of the objects in the following chain are parameters: -\code - x , x.value , x.value.value , ... -\endcode -In such a case, the value of the object will always be the same -no matter what the independent variable values are at any level. - -\param x -values that we are checking for identically a pamameter. - -\return -returns true iff \c x is identically a parameter. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool IdenticalPar(const AD &x) -{ return Parameter(x) && IdenticalPar(x.value_); } -// Zero ============================================================== -/*! -Determine if an AD is equal to zero, -and must be equal zero during any tape playback. - -\param x -object that we are checking. - -\return -returns true if and only if -\c x is equals zero and is identically a parameter \ref CppAD::IdenticalPar. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool IdenticalZero(const AD &x) -{ return Parameter(x) && IdenticalZero(x.value_); } -// One ============================================================== -/*! -Determine if an AD is equal to one, -and must be equal one during any tape playback. - -\param x -object that we are checking. - -\return -returns true if and only if -\c x is equals one and is identically a parameter \ref CppAD::IdenticalPar. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool IdenticalOne(const AD &x) -{ return Parameter(x) && IdenticalOne(x.value_); } -// Equal =================================================================== -/*! -Determine if two AD objects are equal, -and must be equal during any tape playback. - -\param x -first of two objects we are checking for equal. - -\param y -second of two objects we are checking for equal. - -\return -returns true if and only if -the arguments are equal and both identically parameters \ref CppAD::IdenticalPar. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool IdenticalEqualPar -(const AD &x, const AD &y) -{ bool parameter; - parameter = ( Parameter(x) & Parameter(y) ); - return parameter && IdenticalEqualPar(x.value_, y.value_); -} -// ========================================================================== - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/independent.hpp b/ct_core/include/ct/external/cppad/core/independent.hpp deleted file mode 100644 index 544df8615..000000000 --- a/ct_core/include/ct/external/cppad/core/independent.hpp +++ /dev/null @@ -1,176 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_INDEPENDENT_HPP -# define CPPAD_CORE_INDEPENDENT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* ---------------------------------------------------------------------------- - -$begin Independent$$ -$spell - op - alloc - num - Cpp - bool - const - var - typename -$$ - -$section Declare Independent Variables and Start Recording$$ - -$head Syntax$$ -$codei%Independent(%x%) -%$$ -$codei%Independent(%x%, %abort_op_index%) -%$$ - -$head Purpose$$ -Start recording -$cref/AD of Base/glossary/AD of Base/$$ operations -with $icode x$$ as the independent variable vector. -Once the -$cref/operation sequence/glossary/Operation/Sequence/$$ is completed, -it must be transferred to a function object; see below. - -$head Start Recording$$ -An operation sequence recording is started by the commands -$codei% - Independent(%x%) - Independent(%x%, %abort_op_index%) -%$$ - -$head Stop Recording$$ -The recording is stopped, -and the operation sequence is transferred to the AD function object $icode f$$, -using either the $cref/function constructor/FunConstruct/$$ -$codei% - ADFun<%Base%> %f%(%x%, %y%) -%$$ -or the $cref/dependent variable specifier/Dependent/$$ -$codei% - %f%.Dependent(%x%, %y%) -%$$ -The only other way to stop a recording is using -$cref abort_recording$$. -Between when the recording is started and when it stopped, -we refer to the elements of $icode x$$, -and the values that depend on the elements of $icode x$$, -as $codei%AD<%Base%>%$$ variables. - -$head x$$ -The vector $icode x$$ has prototype -$codei% - %VectorAD% &%x% -%$$ -(see $icode VectorAD$$ below). -The size of the vector $icode x$$, must be greater than zero, -and is the number of independent variables for this -AD operation sequence. - -$head abort_op_index$$ -It specifies the operator index at which the execution is be aborted -by calling the CppAD $cref/error handler/ErrorHandler/$$. -When this error handler leads to an assert, the user -can inspect the call stack to see the source code corresponding to -this operator index; see -$cref/purpose/compare_change/op_index/Purpose/$$. -No abort will occur if $icode abort_op_index$$ is zero, -of if $cref/NDEBUG/Faq/Speed/NDEBUG/$$ is defined. - -$head VectorAD$$ -The type $icode VectorAD$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$codei%AD<%Base%>%$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Parallel Mode$$ -Each thread can have one, and only one, active recording. -A call to $code Independent$$ starts the recording for the current thread. -The recording must be stopped by a corresponding call to -$codei% - ADFun<%Base%> %f%( %x%, %y%) -%$$ -or -$codei% - %f%.Dependent( %x%, %y%) -%$$ -or $cref abort_recording$$ -preformed by the same thread; i.e., -$cref/thread_alloc::thread_num/ta_thread_num/$$ must be the same. - -$head Example$$ -$children% - example/independent.cpp -%$$ -The file -$cref independent.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------ -*/ -# include -/*! -\file core/independent.hpp -Declare the independent variables -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -/*! -Declaration of independent variables. - -\tparam VectorAD -This is simple vector type with elements of type AD. - -\param x -Vector of the independent variablerd. - -\param abort_op_index -operator index at which execution will be aborted (during the recording -of operations). The value zero corresponds to not aborting (will not match). -*/ -template -inline void Independent(VectorAD &x, size_t abort_op_index) -{ typedef typename VectorAD::value_type ADBase; - typedef typename ADBase::value_type Base; - CPPAD_ASSERT_KNOWN( - ADBase::tape_ptr() == CPPAD_NULL, - "Independent: cannot create a new tape because\n" - "a previous tape is still active (for this thread).\n" - "AD::abort_recording() would abort this previous recording." - ); - local::ADTape* tape = ADBase::tape_manage(tape_manage_new); - tape->Independent(x, abort_op_index); -} -/*! -Declaration of independent variables without abort option. - -\tparam VectorAD -This is simple vector type with elements of type AD. - -\param x -Vector of the independent variablerd. -*/ -template -inline void Independent(VectorAD &x) -{ size_t abort_op_index = 0; - Independent(x, abort_op_index); -} - -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/core/integer.hpp b/ct_core/include/ct/external/cppad/core/integer.hpp deleted file mode 100644 index 3b71daa1d..000000000 --- a/ct_core/include/ct/external/cppad/core/integer.hpp +++ /dev/null @@ -1,113 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_INTEGER_HPP -# define CPPAD_CORE_INTEGER_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ------------------------------------------------------------------------------- -$begin Integer$$ -$spell - std - VecAD - CppAD - namespace - const - bool -$$ - - - -$section Convert From AD to Integer$$ - -$head Syntax$$ -$icode%i% = Integer(%x%)%$$ - - -$head Purpose$$ -Converts from an AD type to the corresponding integer value. - -$head i$$ -The result $icode i$$ has prototype -$codei% - int %i% -%$$ - -$head x$$ - -$subhead Real Types$$ -If the argument $icode x$$ has either of the following prototypes: -$codei% - const float %% &%x% - const double %% &%x% -%$$ -the fractional part is dropped to form the integer value. -For example, if $icode x$$ is 1.5, $icode i$$ is 1. -In general, if $latex x \geq 0$$, $icode i$$ is the -greatest integer less than or equal $icode x$$. -If $latex x \leq 0$$, $icode i$$ is the -smallest integer greater than or equal $icode x$$. - -$subhead Complex Types$$ -If the argument $icode x$$ has either of the following prototypes: -$codei% - const std::complex %% &%x% - const std::complex %% &%x% -%$$ -The result $icode i$$ is given by -$codei% - %i% = Integer(%x%.real()) -%$$ - -$subhead AD Types$$ -If the argument $icode x$$ has either of the following prototypes: -$codei% - const AD<%Base%> &%x% - const VecAD<%Base%>::reference &%x% -%$$ -$icode Base$$ must support the $code Integer$$ function and -the conversion has the same meaning as for $icode Base$$. - -$head Operation Sequence$$ -The result of this operation is not an -$cref/AD of Base/glossary/AD of Base/$$ object. -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Example$$ -$children% - example/integer.cpp -%$$ -The file -$cref integer.cpp$$ -contains an example and test of this operation. - -$end ------------------------------------------------------------------------------- -*/ - - -namespace CppAD { - - template - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION - int Integer(const AD &x) - { return Integer(x.value_); } - - template - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION - int Integer(const VecAD_reference &x) - { return Integer( x.ADBase() ); } -} -# endif - diff --git a/ct_core/include/ct/external/cppad/core/jacobian.hpp b/ct_core/include/ct/external/cppad/core/jacobian.hpp deleted file mode 100644 index 5f756884f..000000000 --- a/ct_core/include/ct/external/cppad/core/jacobian.hpp +++ /dev/null @@ -1,234 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_JACOBIAN_HPP -# define CPPAD_CORE_JACOBIAN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Jacobian$$ -$spell - jac - typename - Taylor - Jacobian - DetLu - const -$$ - - -$section Jacobian: Driver Routine$$ -$mindex Jacobian first derivative$$ - -$head Syntax$$ -$icode%jac% = %f%.Jacobian(%x%)%$$ - - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -The syntax above sets $icode jac$$ to the -Jacobian of $icode F$$ evaluated at $icode x$$; i.e., -$latex \[ - jac = F^{(1)} (x) -\] $$ - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/Forward or Reverse/Jacobian/Forward or Reverse/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -(see $cref/Vector/Jacobian/Vector/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the Jacobian. - -$head jac$$ -The result $icode jac$$ has prototype -$codei% - %Vector% %jac% -%$$ -(see $cref/Vector/Jacobian/Vector/$$ below) -and its size is $latex m * n$$; i.e., the product of the -$cref/domain/seq_property/Domain/$$ -and -$cref/range/seq_property/Range/$$ -dimensions for $icode f$$. -For $latex i = 0 , \ldots , m - 1 $$ -and $latex j = 0 , \ldots , n - 1$$ -$latex \[. - jac[ i * n + j ] = \D{ F_i }{ x_j } ( x ) -\] $$ - - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Base$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Forward or Reverse$$ -This will use order zero Forward mode and either -order one Forward or order one Reverse to compute the Jacobian -(depending on which it estimates will require less work). -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to $code Jacobian$$, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0, %x%)%$$ -and the other coefficients are unspecified. - -$head Example$$ -$children% - example/jacobian.cpp -%$$ -The routine -$cref/Jacobian/jacobian.cpp/$$ is both an example and test. -It returns $code true$$, if it succeeds and $code false$$ otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -void JacobianFor(ADFun &f, const Vector &x, Vector &jac) -{ size_t i; - size_t j; - - size_t n = f.Domain(); - size_t m = f.Range(); - - // check Vector is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_UNKNOWN( size_t(x.size()) == f.Domain() ); - CPPAD_ASSERT_UNKNOWN( size_t(jac.size()) == f.Range() * f.Domain() ); - - // argument and result for forward mode calculations - Vector u(n); - Vector v(m); - - // initialize all the components - for(j = 0; j < n; j++) - u[j] = Base(0); - - // loop through the different coordinate directions - for(j = 0; j < n; j++) - { // set u to the j-th coordinate direction - u[j] = Base(1); - - // compute the partial of f w.r.t. this coordinate direction - v = f.Forward(1, u); - - // reset u to vector of all zeros - u[j] = Base(0); - - // return the result - for(i = 0; i < m; i++) - jac[ i * n + j ] = v[i]; - } -} -template -void JacobianRev(ADFun &f, const Vector &x, Vector &jac) -{ size_t i; - size_t j; - - size_t n = f.Domain(); - size_t m = f.Range(); - - CPPAD_ASSERT_UNKNOWN( size_t(x.size()) == f.Domain() ); - CPPAD_ASSERT_UNKNOWN( size_t(jac.size()) == f.Range() * f.Domain() ); - - // argument and result for reverse mode calculations - Vector u(n); - Vector v(m); - - // initialize all the components - for(i = 0; i < m; i++) - v[i] = Base(0); - - // loop through the different coordinate directions - for(i = 0; i < m; i++) - { if( f.Parameter(i) ) - { // return zero for this component of f - for(j = 0; j < n; j++) - jac[ i * n + j ] = Base(0); - } - else - { - // set v to the i-th coordinate direction - v[i] = Base(1); - - // compute the derivative of this component of f - u = f.Reverse(1, v); - - // reset v to vector of all zeros - v[i] = Base(0); - - // return the result - for(j = 0; j < n; j++) - jac[ i * n + j ] = u[j]; - } - } -} - -template -template -Vector ADFun::Jacobian(const Vector &x) -{ size_t i; - size_t n = Domain(); - size_t m = Range(); - - CPPAD_ASSERT_KNOWN( - size_t(x.size()) == n, - "Jacobian: length of x not equal domain dimension for F" - ); - - // point at which we are evaluating the Jacobian - Forward(0, x); - - // work factor for forward mode - size_t workForward = n; - - // work factor for reverse mode - size_t workReverse = 0; - for(i = 0; i < m; i++) - { if( ! Parameter(i) ) - ++workReverse; - } - - // choose the method with the least work - Vector jac( n * m ); - if( workForward <= workReverse ) - JacobianFor(*this, x, jac); - else JacobianRev(*this, x, jac); - - return jac; -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/log1p.hpp b/ct_core/include/ct/external/cppad/core/log1p.hpp deleted file mode 100644 index 921773be8..000000000 --- a/ct_core/include/ct/external/cppad/core/log1p.hpp +++ /dev/null @@ -1,92 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_LOG1P_HPP -# define CPPAD_CORE_LOG1P_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin log1p$$ -$spell - CppAD -$$ - -$section The Logarithm of One Plus Argument: log1p$$ - -$head Syntax$$ -$icode%y% = log1p(%x%)%$$ - -$head Description$$ -Returns the value of the logarithm of one plus argument which is defined -by $icode%y% == log(1 + %x%)%$$. - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head CPPAD_USE_CPLUSPLUS_2011$$ - -$subhead true$$ -If this preprocessor symbol is true ($code 1$$), -and $icode x$$ is an AD type, -this is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$subhead false$$ -If this preprocessor symbol is false ($code 0$$), -CppAD uses the representation -$latex \[ -\R{log1p} (x) = \log(1 + x) -\] $$ -to compute this function. - -$head Example$$ -$children% - example/log1p.cpp -%$$ -The file -$cref log1p.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ -# include -# if ! CPPAD_USE_CPLUSPLUS_2011 - -// BEGIN CppAD namespace -namespace CppAD { - -template -Type log1p_template(const Type &x) -{ return CppAD::log(Type(1) + x); -} - -inline float log1p(const float &x) -{ return log1p_template(x); } - -inline double log1p(const double &x) -{ return log1p_template(x); } - -template -inline AD log1p(const AD &x) -{ return log1p_template(x); } - -template -inline AD log1p(const VecAD_reference &x) -{ return log1p_template( x.ADBase() ); } - - -} // END CppAD namespace - -# endif // CPPAD_USE_CPLUSPLUS_2011 -# endif // CPPAD_LOG1P_INCLUDED diff --git a/ct_core/include/ct/external/cppad/core/lu_ratio.hpp b/ct_core/include/ct/external/cppad/core/lu_ratio.hpp deleted file mode 100644 index 03f366f10..000000000 --- a/ct_core/include/ct/external/cppad/core/lu_ratio.hpp +++ /dev/null @@ -1,337 +0,0 @@ -# ifndef CPPAD_CORE_LU_RATIO_HPP -# define CPPAD_CORE_LU_RATIO_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-17 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin LuRatio$$ -$spell - cppad.hpp - xk - Cpp - Lu - bool - const - ip - jp - std - ADvector -$$ - - -$section LU Factorization of A Square Matrix and Stability Calculation$$ -$mindex LuRatio linear equation solve$$ - -$head Syntax$$ -$code# include $$ -$pre -$$ -$icode%sign% = LuRatio(%ip%, %jp%, %LU%, %ratio%)%$$ - - -$head Description$$ -Computes an LU factorization of the matrix $icode A$$ -where $icode A$$ is a square matrix. -A measure of the numerical stability called $icode ratio$$ is calculated. -This ratio is useful when the results of $code LuRatio$$ are -used as part of an $cref ADFun$$ object. - -$head Include$$ -This routine is designed to be used with AD objects and -requires the $code cppad/cppad.hpp$$ file to be included. - -$head Matrix Storage$$ -All matrices are stored in row major order. -To be specific, if $latex Y$$ is a vector -that contains a $latex p$$ by $latex q$$ matrix, -the size of $latex Y$$ must be equal to $latex p * q $$ and for -$latex i = 0 , \ldots , p-1$$, -$latex j = 0 , \ldots , q-1$$, -$latex \[ - Y_{i,j} = Y[ i * q + j ] -\] $$ - -$head sign$$ -The return value $icode sign$$ has prototype -$codei% - int %sign% -%$$ -If $icode A$$ is invertible, $icode sign$$ is plus or minus one -and is the sign of the permutation corresponding to the row ordering -$icode ip$$ and column ordering $icode jp$$. -If $icode A$$ is not invertible, $icode sign$$ is zero. - -$head ip$$ -The argument $icode ip$$ has prototype -$codei% - %SizeVector% &%ip% -%$$ -(see description of $cref/SizeVector/LuFactor/SizeVector/$$ below). -The size of $icode ip$$ is referred to as $icode n$$ in the -specifications below. -The input value of the elements of $icode ip$$ does not matter. -The output value of the elements of $icode ip$$ determine -the order of the rows in the permuted matrix. - -$head jp$$ -The argument $icode jp$$ has prototype -$codei% - %SizeVector% &%jp% -%$$ -(see description of $cref/SizeVector/LuFactor/SizeVector/$$ below). -The size of $icode jp$$ must be equal to $icode n$$. -The input value of the elements of $icode jp$$ does not matter. -The output value of the elements of $icode jp$$ determine -the order of the columns in the permuted matrix. - -$head LU$$ -The argument $icode LU$$ has the prototype -$codei% - %ADvector% &%LU% -%$$ -and the size of $icode LU$$ must equal $latex n * n$$ -(see description of $cref/ADvector/LuRatio/ADvector/$$ below). - -$subhead A$$ -We define $icode A$$ as the matrix corresponding to the input -value of $icode LU$$. - -$subhead P$$ -We define the permuted matrix $icode P$$ in terms of $icode A$$ by -$codei% - %P%(%i%, %j%) = %A%[ %ip%[%i%] * %n% + %jp%[%j%] ] -%$$ - -$subhead L$$ -We define the lower triangular matrix $icode L$$ in terms of the -output value of $icode LU$$. -The matrix $icode L$$ is zero above the diagonal -and the rest of the elements are defined by -$codei% - %L%(%i%, %j%) = %LU%[ %ip%[%i%] * %n% + %jp%[%j%] ] -%$$ -for $latex i = 0 , \ldots , n-1$$ and $latex j = 0 , \ldots , i$$. - -$subhead U$$ -We define the upper triangular matrix $icode U$$ in terms of the -output value of $icode LU$$. -The matrix $icode U$$ is zero below the diagonal, -one on the diagonal, -and the rest of the elements are defined by -$codei% - %U%(%i%, %j%) = %LU%[ %ip%[%i%] * %n% + %jp%[%j%] ] -%$$ -for $latex i = 0 , \ldots , n-2$$ and $latex j = i+1 , \ldots , n-1$$. - -$subhead Factor$$ -If the return value $icode sign$$ is non-zero, -$codei% - %L% * %U% = %P% -%$$ -If the return value of $icode sign$$ is zero, -the contents of $icode L$$ and $icode U$$ are not defined. - -$subhead Determinant$$ -If the return value $icode sign$$ is zero, -the determinant of $icode A$$ is zero. -If $icode sign$$ is non-zero, -using the output value of $icode LU$$ -the determinant of the matrix $icode A$$ is equal to -$codei% -%sign% * %LU%[%ip%[0], %jp%[0]] * %...% * %LU%[%ip%[%n%-1], %jp%[%n%-1]] -%$$ - -$head ratio$$ -The argument $icode ratio$$ has prototype -$codei% - AD<%Base%> &%ratio% -%$$ -On input, the value of $icode ratio$$ does not matter. -On output it is a measure of how good the choice of pivots is. -For $latex p = 0 , \ldots , n-1$$, -the $th p$$ pivot element is the element of maximum absolute value of a -$latex (n-p) \times (n-p)$$ sub-matrix. -The ratio of each element of sub-matrix divided by the pivot element -is computed. -The return value of $icode ratio$$ is the maximum absolute value of -such ratios over with respect to all elements and all the pivots. - -$subhead Purpose$$ -Suppose that the execution of a call to $code LuRatio$$ -is recorded in the $codei%ADFun<%Base%>%$$ object $icode F$$. -Then a call to $cref Forward$$ of the form -$codei% - %F%.Forward(%k%, %xk%) -%$$ -with $icode k$$ equal to zero will revaluate this Lu factorization -with the same pivots and a new value for $icode A$$. -In this case, the resulting $icode ratio$$ may not be one. -If $icode ratio$$ is too large (the meaning of too large is up to you), -the current pivots do not yield a stable LU factorization of $icode A$$. -A better choice for the pivots (for this value of $icode A$$) -will be made if you recreate the $code ADFun$$ object -starting with the $cref Independent$$ variable values -that correspond to the vector $icode xk$$. - -$head SizeVector$$ -The type $icode SizeVector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type size_t/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head ADvector$$ -The type $icode ADvector$$ must be a -$cref/simple vector class/SimpleVector/$$ with elements of type -$codei%AD<%Base%>%$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - - -$head Example$$ -$children% - example/lu_ratio.cpp -%$$ -The file $cref lu_ratio.cpp$$ -contains an example and test of using $code LuRatio$$. -It returns true if it succeeds and false otherwise. - -$end --------------------------------------------------------------------------- -*/ -namespace CppAD { // BEGIN CppAD namespace - -// Lines different from the code in cppad/lu_factor.hpp end with // -template // -int LuRatio(SizeVector &ip, SizeVector &jp, ADvector &LU, AD &ratio) // -{ - typedef ADvector FloatVector; // - typedef AD Float; // - - // check numeric type specifications - CheckNumericType(); - - // check simple vector class specifications - CheckSimpleVector(); - CheckSimpleVector(); - - size_t i, j; // some temporary indices - const Float zero( 0 ); // the value zero as a Float object - size_t imax; // row index of maximum element - size_t jmax; // column indx of maximum element - Float emax; // maximum absolute value - size_t p; // count pivots - int sign; // sign of the permutation - Float etmp; // temporary element - Float pivot; // pivot element - - // ------------------------------------------------------- - size_t n = size_t(ip.size()); - CPPAD_ASSERT_KNOWN( - size_t(jp.size()) == n, - "Error in LuFactor: jp must have size equal to n" - ); - CPPAD_ASSERT_KNOWN( - size_t(LU.size()) == n * n, - "Error in LuFactor: LU must have size equal to n * m" - ); - // ------------------------------------------------------- - - // initialize row and column order in matrix not yet pivoted - for(i = 0; i < n; i++) - { ip[i] = i; - jp[i] = i; - } - // initialize the sign of the permutation - sign = 1; - // initialize the ratio // - ratio = Float(1); // - // --------------------------------------------------------- - - // Reduce the matrix P to L * U using n pivots - for(p = 0; p < n; p++) - { // determine row and column corresponding to element of - // maximum absolute value in remaining part of P - imax = jmax = n; - emax = zero; - for(i = p; i < n; i++) - { for(j = p; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( - (ip[i] < n) & (jp[j] < n) - ); - etmp = LU[ ip[i] * n + jp[j] ]; - - // check if maximum absolute value so far - if( AbsGeq (etmp, emax) ) - { imax = i; - jmax = j; - emax = etmp; - } - } - } - for(i = p; i < n; i++) // - { for(j = p; j < n; j++) // - { etmp = fabs(LU[ ip[i] * n + jp[j] ] / emax); // - ratio = // - CondExpGt(etmp, ratio, etmp, ratio); // - } // - } // - CPPAD_ASSERT_KNOWN( - (imax < n) & (jmax < n) , - "AbsGeq must return true when second argument is zero" - ); - if( imax != p ) - { // switch rows so max absolute element is in row p - i = ip[p]; - ip[p] = ip[imax]; - ip[imax] = i; - sign = -sign; - } - if( jmax != p ) - { // switch columns so max absolute element is in column p - j = jp[p]; - jp[p] = jp[jmax]; - jp[jmax] = j; - sign = -sign; - } - // pivot using the max absolute element - pivot = LU[ ip[p] * n + jp[p] ]; - - // check for determinant equal to zero - if( pivot == zero ) - { // abort the mission - return 0; - } - - // Reduce U by the elementary transformations that maps - // LU( ip[p], jp[p] ) to one. Only need transform elements - // above the diagonal in U and LU( ip[p] , jp[p] ) is - // corresponding value below diagonal in L. - for(j = p+1; j < n; j++) - LU[ ip[p] * n + jp[j] ] /= pivot; - - // Reduce U by the elementary transformations that maps - // LU( ip[i], jp[p] ) to zero. Only need transform elements - // above the diagonal in U and LU( ip[i], jp[p] ) is - // corresponding value below diagonal in L. - for(i = p+1; i < n; i++ ) - { etmp = LU[ ip[i] * n + jp[p] ]; - for(j = p+1; j < n; j++) - { LU[ ip[i] * n + jp[j] ] -= - etmp * LU[ ip[p] * n + jp[j] ]; - } - } - } - return sign; -} -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/mul.hpp b/ct_core/include/ct/external/cppad/core/mul.hpp deleted file mode 100644 index ece04e369..000000000 --- a/ct_core/include/ct/external/cppad/core/mul.hpp +++ /dev/null @@ -1,102 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_MUL_HPP -# define CPPAD_CORE_MUL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD operator * (const AD &left , const AD &right) -{ - // compute the Base part - AD result; - result.value_ = left.value_ * right.value_; - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - // check if there is a recording in progress - local::ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return result; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = left.tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // result = variable * variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::MulvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::MulvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(left.taddr_, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::MulvvOp); - // make result a variable - result.tape_id_ = tape_id; - } - else if( IdenticalZero(right.value_) ) - { // result = variable * 0 - } - else if( IdenticalOne(right.value_) ) - { // result = variable * 1 - result.make_variable(left.tape_id_, left.taddr_); - } - else - { // result = variable * parameter - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::MulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::MulpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(p, left.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::MulpvOp); - // make result a variable - result.tape_id_ = tape_id; - } - } - else if( var_right ) - { if( IdenticalZero(left.value_) ) - { // result = 0 * variable - } - else if( IdenticalOne(left.value_) ) - { // result = 1 * variable - result.make_variable(right.tape_id_, right.taddr_); - } - else - { // result = parameter * variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::MulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::MulpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left.value_); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::MulpvOp); - // make result a variable - result.tape_id_ = tape_id; - } - } - return result; -} - -// convert other cases into the case above -CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR(*) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/mul_eq.hpp b/ct_core/include/ct/external/cppad/core/mul_eq.hpp deleted file mode 100644 index cd4c9f1de..000000000 --- a/ct_core/include/ct/external/cppad/core/mul_eq.hpp +++ /dev/null @@ -1,102 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_MUL_EQ_HPP -# define CPPAD_CORE_MUL_EQ_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD& AD::operator *= (const AD &right) -{ - // compute the Base part - Base left; - left = value_; - value_ *= right.value_; - - // check if there is a recording in progress - local::ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return *this; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // this = variable * variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::MulvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::MulvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(taddr_, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(local::MulvvOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - else if( IdenticalOne( right.value_ ) ) - { // this = variable * 1 - } - else if( IdenticalZero( right.value_ ) ) - { // this = variable * 0 - make_parameter(); - } - else - { // this = variable * parameter - // = parameter * variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::MulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::MulpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(p, taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(local::MulpvOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - } - else if( var_right ) - { if( IdenticalZero(left) ) - { // this = 0 * right - } - else if( IdenticalOne(left) ) - { // this = 1 * right - make_variable(right.tape_id_, right.taddr_); - } - else - { // this = parameter * variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::MulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::MulpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(local::MulpvOp); - // make this a variable - tape_id_ = tape_id; - } - } - return *this; -} - -CPPAD_FOLD_ASSIGNMENT_OPERATOR(*=) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/near_equal_ext.hpp b/ct_core/include/ct/external/cppad/core/near_equal_ext.hpp deleted file mode 100644 index eda406d0f..000000000 --- a/ct_core/include/ct/external/cppad/core/near_equal_ext.hpp +++ /dev/null @@ -1,189 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_NEAR_EQUAL_EXT_HPP -# define CPPAD_CORE_NEAR_EQUAL_EXT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin NearEqualExt$$ -$spell - cout - endl - Microsoft - std - Cpp - namespace - const - bool -$$ - -$section Compare AD and Base Objects for Nearly Equal$$ -$mindex NearEqual with$$ - - -$head Syntax$$ -$icode%b% = NearEqual(%x%, %y%, %r%, %a%)%$$ - - -$head Purpose$$ -The routine $cref NearEqual$$ determines if two objects of -the same type are nearly. -This routine is extended to the case where one object can have type -$icode Type$$ while the other can have type -$codei%AD<%Type%>%$$ or -$codei%AD< std::complex<%Type%> >%$$. - -$head x$$ -The arguments $icode x$$ -has one of the following possible prototypes: -$codei% - const %Type% &%x% - const AD<%Type%> &%x% - const AD< std::complex<%Type%> > &%x% -%$$ - -$head y$$ -The arguments $icode y$$ -has one of the following possible prototypes: -$codei% - const %Type% &%y% - const AD<%Type%> &%y% - const AD< std::complex<%Type%> > &%x% -%$$ - - -$head r$$ -The relative error criteria $icode r$$ has prototype -$codei% - const %Type% &%r% -%$$ -It must be greater than or equal to zero. -The relative error condition is defined as: -$latex \[ - \frac{ | x - y | } { |x| + |y| } \leq r -\] $$ - -$head a$$ -The absolute error criteria $icode a$$ has prototype -$codei% - const %Type% &%a% -%$$ -It must be greater than or equal to zero. -The absolute error condition is defined as: -$latex \[ - | x - y | \leq a -\] $$ - -$head b$$ -The return value $icode b$$ has prototype -$codei% - bool %b% -%$$ -If either $icode x$$ or $icode y$$ is infinite or not a number, -the return value is false. -Otherwise, if either the relative or absolute error -condition (defined above) is satisfied, the return value is true. -Otherwise, the return value is false. - -$head Type$$ -The type $icode Type$$ must be a -$cref NumericType$$. -The routine $cref CheckNumericType$$ will generate -an error message if this is not the case. -If $icode a$$ and $icode b$$ have type $icode Type$$, -the following operation must be defined -$table -$bold Operation$$ $cnext - $bold Description$$ $rnext -$icode%a% <= %b%$$ $cnext - less that or equal operator (returns a $code bool$$ object) -$tend - -$head Operation Sequence$$ -The result of this operation is not an -$cref/AD of Base/glossary/AD of Base/$$ object. -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Example$$ -$children% - example/near_equal_ext.cpp -%$$ -The file $cref near_equal_ext.cpp$$ contains an example -and test of this extension of $cref NearEqual$$. -It return true if it succeeds and false otherwise. - -$end - -*/ -// BEGIN CppAD namespace -namespace CppAD { -// ------------------------------------------------------------------------ - -// fold into base type and then use -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual( -const AD &x, const AD &y, const Base &r, const Base &a) -{ return NearEqual(x.value_, y.value_, r, a); -} - -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual( -const Base &x, const AD &y, const Base &r, const Base &a) -{ return NearEqual(x, y.value_, r, a); -} - -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual( -const AD &x, const Base &y, const Base &r, const Base &a) -{ return NearEqual(x.value_, y, r, a); -} - -// fold into AD type and then use cases above -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual( - const VecAD_reference &x, const VecAD_reference &y, - const Base &r, const Base &a) -{ return NearEqual(x.ADBase(), y.ADBase(), r, a); -} -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual(const VecAD_reference &x, const AD &y, - const Base &r, const Base &a) -{ return NearEqual(x.ADBase(), y, r, a); -} -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual(const VecAD_reference &x, const Base &y, - const Base &r, const Base &a) -{ return NearEqual(x.ADBase(), y, r, a); -} -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual(const AD &x, const VecAD_reference &y, - const Base &r, const Base &a) -{ return NearEqual(x, y.ADBase(), r, a); -} -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual(const Base &x, const VecAD_reference &y, - const Base &r, const Base &a) -{ return NearEqual(x, y.ADBase(), r, a); -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/num_skip.hpp b/ct_core/include/ct/external/cppad/core/num_skip.hpp deleted file mode 100644 index e2d9f5803..000000000 --- a/ct_core/include/ct/external/cppad/core/num_skip.hpp +++ /dev/null @@ -1,130 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_NUM_SKIP_HPP -# define CPPAD_CORE_NUM_SKIP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin number_skip$$ -$spell - optimizer - var - taylor_ -$$ - - -$section Number of Variables that Can be Skipped$$ -$mindex number_skip$$ - -$head Syntax$$ -$icode%n% = %f%.number_skip()%$$ - -$subhead See Also$$ -$cref seq_property$$ - -$head Purpose$$ -The $cref/conditional expressions/CondExp/$$ use either the -$cref/if_true/CondExp/$$ or $cref/if_false/CondExp/$$. -Hence, some terms only need to be evaluated -depending on the value of the comparison in the conditional expression. -The $cref optimize$$ option is capable of detecting some of these -case and determining variables that can be skipped. -This routine returns the number such variables. - -$head n$$ -The return value $icode n$$ has type $code size_t$$ -is the number of variables that the optimizer has determined can be skipped -(given the independent variable values specified by the previous call to -$cref/f.Forward/Forward/$$ for order zero). - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ - -$children% - example/number_skip.cpp -%$$ -$head Example$$ -The file $cref number_skip.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -// This routine is not const because it runs through the operations sequence -// 2DO: compute this value during zero order forward operations. -template -size_t ADFun::number_skip(void) -{ // must pass through operation sequence to map operations to variables - local::OpCode op; - size_t i_op; - size_t i_var; - const addr_t* arg; - - // information defined by forward_user - size_t user_old=0, user_m=0, user_n=0, user_i=0, user_j=0; - local::enum_user_state user_state; - - // number of variables skipped - size_t num_var_skip = 0; - - // start playback - user_state = local::start_user; - play_.forward_start(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN(op == local::BeginOp) - while(op != local::EndOp) - { // next op - play_.forward_next(op, arg, i_op, i_var); - // - if( op == local::UserOp ) - { // skip only appears at front or back UserOp of user atomic call - bool skip_call = cskip_op_[i_op]; - CPPAD_ASSERT_UNKNOWN( user_state == local::start_user ); - play_.forward_user( - op, user_state, user_old, user_m, user_n, user_i, user_j - ); - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 0 ); - size_t num_op = user_m + user_n + 1; - for(size_t i = 0; i < num_op; i++) - { play_.forward_next(op, arg, i_op, i_var); - play_.forward_user( - op, user_state, user_old, user_m, user_n, user_i, user_j - ); - if( skip_call ) - num_var_skip += NumRes(op); - } - CPPAD_ASSERT_UNKNOWN( user_state == local::start_user ); - } - else - { if( op == local::CSumOp) - play_.forward_csum(op, arg, i_op, i_var); - else if (op == local::CSkipOp) - play_.forward_cskip(op, arg, i_op, i_var); - // - if( cskip_op_[i_op] ) - num_var_skip += NumRes(op); - } - } - return num_var_skip; -} - -} // END CppAD namespace - - -# endif diff --git a/ct_core/include/ct/external/cppad/core/numeric_limits.hpp b/ct_core/include/ct/external/cppad/core/numeric_limits.hpp deleted file mode 100644 index 0edf5a88b..000000000 --- a/ct_core/include/ct/external/cppad/core/numeric_limits.hpp +++ /dev/null @@ -1,199 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_NUMERIC_LIMITS_HPP -# define CPPAD_CORE_NUMERIC_LIMITS_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ------------------------------------------------------------------------------- -$begin numeric_limits$$ -$spell - std - eps - CppAD - namespace - const -$$ - -$section Numeric Limits For an AD and Base Types$$ - -$head Syntax$$ -$icode%eps% = numeric_limits<%Float%>::epsilon() -%$$ -$icode%min% = numeric_limits<%Float%>::min() -%$$ -$icode%max% = numeric_limits<%Float%>::max() -%$$ -$icode%nan% = numeric_limits<%Float%>::quiet_NaN() -%$$ - -$head CppAD::numeric_limits$$ -These functions and have the prototype -$codei% - static %Float% CppAD::numeric_limits<%Float%>::%fun%(%void%) -%$$ -where $icode fun$$ is -$code epsilon$$, $code min$$, $code max$$, and $code quiet_NaN$$. - -$head std::numeric_limits$$ -CppAD does not use a specialization of $code std::numeric_limits$$ -because this would be to restrictive. -The C++ standard specifies that Non-fundamental standard -types, such as -$cref/std::complex/base_complex.hpp/$$ shall not have specializations -of $code std::numeric_limits$$; see Section 18.2 of -ISO/IEC 14882:1998(E). -In addition, since C++11, a only literal types can have a specialization -of $code std::numeric_limits$$. - -$head Float$$ -These functions are defined for all $codei%AD<%Base%>%$$, -and for all corresponding $icode Base$$ types; -see $icode Base$$ type $cref base_limits$$. - -$head epsilon$$ -The result $icode eps$$ is equal to machine epsilon and has prototype -$codei% - %Float% %eps% -%$$ -The file $cref num_limits.cpp$$ -tests the value $icode eps$$ by checking that the following are true -$codei% - 1 != 1 + %eps% - 1 == 1 + %eps% / 2 -%$$ -where all the values, and calculations, are done with the precision -corresponding to $icode Float$$. - -$head min$$ -The result $icode min$$ is equal to -the minimum positive normalized value and has prototype -$codei% - %Float% %min% -%$$ -The file $cref num_limits.cpp$$ -tests the value $icode min$$ by checking that the following are true -$codei% - abs( ((%min% / 100) * 100) / %min% - 1 ) > 3 * %eps% - abs( ((%min% * 100) / 100) / %min% - 1 ) < 3 * %eps% -%$$ -where all the values, and calculations, are done with the precision -corresponding to $icode Float$$. - -$head max$$ -The result $icode max$$ is equal to -the maximum finite value and has prototype -$codei% - %Float% %max% -%$$ -The file $cref num_limits.cpp$$ -tests the value $icode max$$ by checking that the following are true -$codei% - abs( ((%max% * 100) / 100) / %max% - 1 ) > 3 * %eps% - abs( ((%max% / 100) * 100) / %max% - 1 ) < 3 * %eps% -%$$ -where all the values, and calculations, are done with the precision -corresponding to $icode Float$$. - -$head quiet_NaN$$ -The result $icode nan$$ is not a number and has prototype -$codei% - %Float% %nan% -%$$ -The file $cref num_limits.cpp$$ -tests the value $icode nan$$ by checking that the following is true -$codei% - %nan% != %nan% -%$$ - - -$head Example$$ -$children% - example/num_limits.cpp -%$$ -The file -$cref num_limits.cpp$$ -contains an example and test of these functions. - -$end ------------------------------------------------------------------------------- -*/ -# include - -# include -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file numeric_limits.hpp -File that defines CppAD numeric_limits for AD types -*/ - -/// Default value for all undefined numeric_limits types -template -class numeric_limits { -public: - /// machine epsilon - static Float epsilon(void) - { CPPAD_ASSERT_KNOWN( - false, - "numeric_limits::epsilon() is not specialized for this Float" - ); - return Float(0); - } - /// minimum positive normalized value - static Float min(void) - { CPPAD_ASSERT_KNOWN( - false, - "numeric_limits::min() is not specialized for this Float" - ); - return Float(0); - } - /// maximum finite value - static Float max(void) - { CPPAD_ASSERT_KNOWN( - false, - "numeric_limits::max() is not specialized for this Float" - ); - return Float(0); - } - /// not a number - static Float quiet_NaN(void) - { CPPAD_ASSERT_KNOWN( - false, - "numeric_limits::quiet_NaN() is not specialized for this Float" - ); - return Float(0); - } -}; - -/// Partial specialization that defines limits for for all AD types -template -class numeric_limits< AD > { -public: - /// machine epsilon - static AD epsilon(void) - { return AD( numeric_limits::epsilon() ); } - /// minimum positive normalized value - static AD min(void) - { return AD( numeric_limits::min() ); } - /// maximum finite value - static AD max(void) - { return AD( numeric_limits::max() ); } - /// note a number - static AD quiet_NaN(void) - { return AD( numeric_limits::quiet_NaN() ); } -}; - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/old_atomic.hpp b/ct_core/include/ct/external/cppad/core/old_atomic.hpp deleted file mode 100644 index 6847ebbd2..000000000 --- a/ct_core/include/ct/external/cppad/core/old_atomic.hpp +++ /dev/null @@ -1,1089 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_OLD_ATOMIC_HPP -# define CPPAD_CORE_OLD_ATOMIC_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin old_atomic$$ -$spell - hes - std - Jacobian - jac - Tvector - afun - vx - vy - bool - namespace - CppAD - const - Taylor - tx - ty - px - py -$$ - -$section User Defined Atomic AD Functions$$ -$mindex operation old_atomic$$ - -$head Deprecated 2013-05-27$$ -Using $code CPPAD_USER_ATOMIC$$ has been deprecated. -Use $cref atomic_base$$ instead. - -$head Syntax Function$$ -$codei%CPPAD_USER_ATOMIC(%afun%, %Tvector%, %Base%, - %forward%, %reverse%, %for_jac_sparse%, %rev_jac_sparse%, %rev_hes_sparse% -) -%$$ - -$subhead Use Function$$ -$icode%afun%(%id%, %ax%, %ay%) -%$$ - -$subhead Callback Routines$$ -$icode%ok% = %forward%(%id%, %k%, %n%, %m%, %vx%, %vy%, %tx%, %ty%) -%$$ -$icode%ok% = %reverse%(%id%, %k%, %n%, %m%, %tx%, %ty%, %px%, %py%) -%$$ -$icode%ok% = %for_jac_sparse%(%id%, %n%, %m%, %q%, %r%, %s%) -%$$ -$icode%ok% = %rev_jac_sparse%(%id%, %n%, %m%, %q%, %r%, %s%) -%$$ -$icode%ok% = %rev_hes_sparse%(%id%, %n%, %m%, %q%, %r%, %s%, %t%, %u%, %v%) -%$$ - -$subhead Free Static Memory$$ -$codei%user_atomic<%Base%>::clear()%$$ - -$head Purpose$$ -In some cases, the user knows how to compute the derivative -of a function -$latex \[ - y = f(x) \; {\rm where} \; f : B^n \rightarrow B^m -\] $$ -more efficiently than by coding it using $codei%AD<%Base%>%$$ -$cref/atomic/glossary/Operation/Atomic/$$ operations -and letting CppAD do the rest. -In this case, $code CPPAD_USER_ATOMIC$$ can be used -add the user code for $latex f(x)$$, and its derivatives, -to the set of $codei%AD<%Base%>%$$ atomic operations. -$pre - -$$ -Another possible purpose is to reduce the size of the tape; -see $cref/use AD/old_atomic/Example/Use AD/$$ - -$head Partial Implementation$$ -The routines -$cref/forward/old_atomic/forward/$$, -$cref/reverse/old_atomic/reverse/$$, -$cref/for_jac_sparse/old_atomic/for_jac_sparse/$$, -$cref/rev_jac_sparse/old_atomic/rev_jac_sparse/$$, and -$cref/rev_hes_sparse/old_atomic/rev_hes_sparse/$$, -must be defined by the user. -The $icode forward$$ the routine, -for the case $icode%k% = 0%$$, must be implemented. -Functions with the correct prototype, -that just return $code false$$, -can be used for the other cases -(unless they are required by your calculations). -For example, you need not implement -$icode forward$$ for the case $icode%k% == 2%$$ until you require -forward mode calculation of second derivatives. - -$head CPPAD_USER_ATOMIC$$ -The macro -$codei% -CPPAD_USER_ATOMIC(%afun%, %Tvector%, %Base%, - %forward%, %reverse%, %for_jac_sparse%, %rev_jac_sparse%, %rev_hes_sparse% -) -%$$ -defines the $codei%AD<%Base%>%$$ routine $icode afun$$. -This macro can be placed within a namespace -(not the $code CppAD$$ namespace) -but must be outside of any routine. - -$subhead Tvector$$ -The macro argument $icode Tvector$$ must be a -$cref/simple vector template class/SimpleVector/$$. -It determines the type of vectors used as arguments to the routine -$icode afun$$. - -$subhead Base$$ -The macro argument $icode Base$$ specifies the -$cref/base type/base_require/$$ -corresponding to $codei%AD<%Base>%$$ operation sequences. -Calling the routine $icode afun$$ will add the operator defined -by this macro to an $codei%AD<%Base>%$$ operation sequence. - -$head ok$$ -For all routines documented below, -the return value $icode ok$$ has prototype -$codei% - bool %ok% -%$$ -If it is $code true$$, the corresponding evaluation succeeded, -otherwise it failed. - -$head id$$ -For all routines documented below, -the argument $icode id$$ has prototype -$codei% - size_t %id% -%$$ -Its value in all other calls is the same as in the corresponding -call to $icode afun$$. -It can be used to store and retrieve extra information about -a specific call to $icode afun$$. - -$head k$$ -For all routines documented below, the argument $icode k$$ has prototype -$codei% - size_t %k% -%$$ -The value $icode%k%$$ is the order of the Taylor coefficient that -we are evaluating ($cref/forward/old_atomic/forward/$$) -or taking the derivative of ($cref/reverse/old_atomic/reverse/$$). - -$head n$$ -For all routines documented below, -the argument $icode n$$ has prototype -$codei% - size_t %n% -%$$ -It is the size of the vector $icode ax$$ in the corresponding call to -$icode%afun%(%id%, %ax%, %ay%)%$$; i.e., -the dimension of the domain space for $latex y = f(x)$$. - -$head m$$ -For all routines documented below, the argument $icode m$$ has prototype -$codei% - size_t %m% -%$$ -It is the size of the vector $icode ay$$ in the corresponding call to -$icode%afun%(%id%, %ax%, %ay%)%$$; i.e., -the dimension of the range space for $latex y = f(x)$$. - -$head tx$$ -For all routines documented below, -the argument $icode tx$$ has prototype -$codei% - const CppAD::vector<%Base%>& %tx% -%$$ -and $icode%tx%.size() >= (%k% + 1) * %n%$$. -For $latex j = 0 , \ldots , n-1$$ and $latex \ell = 0 , \ldots , k$$, -we use the Taylor coefficient notation -$latex \[ -\begin{array}{rcl} - x_j^\ell & = & tx [ j * ( k + 1 ) + \ell ] - \\ - X_j (t) & = & x_j^0 + x_j^1 t^1 + \cdots + x_j^k t^k -\end{array} -\] $$ -If $icode%tx%.size() > (%k% + 1) * %n%$$, -the other components of $icode tx$$ are not specified and should not be used. -Note that superscripts represent an index for $latex x_j^\ell$$ -and an exponent for $latex t^\ell$$. -Also note that the Taylor coefficients for $latex X(t)$$ correspond -to the derivatives of $latex X(t)$$ at $latex t = 0$$ in the following way: -$latex \[ - x_j^\ell = \frac{1}{ \ell ! } X_j^{(\ell)} (0) -\] $$ - -$head ty$$ -In calls to $cref/forward/old_atomic/forward/$$, -the argument $icode ty$$ has prototype -$codei% - CppAD::vector<%Base%>& %ty% -%$$ -while in calls to $cref/reverse/old_atomic/reverse/$$ it has prototype -$codei% - const CppAD::vector<%Base%>& %ty% -%$$ -For all calls, $icode%tx%.size() >= (%k% + 1) * %m%$$. -For $latex i = 0 , \ldots , m-1$$ and $latex \ell = 0 , \ldots , k$$, -we use the Taylor coefficient notation -$latex \[ -\begin{array}{rcl} - y_i^\ell & = & ty [ i * ( k + 1 ) + \ell ] - \\ - Y_i (t) & = & y_i^0 + y_i^1 t^1 + \cdots + y_i^k t^k + o ( t^k ) -\end{array} -\] $$ -where $latex o( t^k ) / t^k \rightarrow 0$$ as $latex t \rightarrow 0$$. -If $icode%ty%.size() > (%k% + 1) * %m%$$, -the other components of $icode ty$$ are not specified and should not be used. -Note that superscripts represent an index for $latex y_j^\ell$$ -and an exponent for $latex t^\ell$$. -Also note that the Taylor coefficients for $latex Y(t)$$ correspond -to the derivatives of $latex Y(t)$$ at $latex t = 0$$ in the following way: -$latex \[ - y_j^\ell = \frac{1}{ \ell ! } Y_j^{(\ell)} (0) -\] $$ - -$subhead forward$$ -In the case of $icode forward$$, -for $latex i = 0 , \ldots , m-1$$, $latex ty[ i *( k + 1) + k ]$$ is an output -and all the other components of $icode ty$$ are inputs. - -$subhead reverse$$ -In the case of $icode reverse$$, -all the components of $icode ty$$ are inputs. - -$head afun$$ -The macro argument $icode afun$$, -is the name of the AD function corresponding to this atomic -operation (as it is used in the source code). -CppAD uses the other functions, -where the arguments are vectors with elements of type $icode Base$$, -to implement the function -$codei% - %afun%(%id%, %ax%, %ay%) -%$$ -where the argument are vectors with elements of type $codei%AD<%Base%>%$$. - -$subhead ax$$ -The $icode afun$$ argument $icode ax$$ has prototype -$codei% - const %Tvector%< AD<%Base%> >& %ax% -%$$ -It is the argument vector $latex x \in B^n$$ -at which the $codei%AD<%Base%>%$$ version of -$latex y = f(x)$$ is to be evaluated. -The dimension of the domain space for $latex y = f (x)$$ -is specified by $cref/n/old_atomic/n/$$ $codei%= %ax%.size()%$$, -which must be greater than zero. - -$subhead ay$$ -The $icode afun$$ result $icode ay$$ has prototype -$codei% - %Tvector%< AD<%Base%> >& %ay% -%$$ -The input values of its elements -are not specified (must not matter). -Upon return, it is the $codei%AD<%Base%>%$$ version of the -result vector $latex y = f(x)$$. -The dimension of the range space for $latex y = f (x)$$ -is specified by $cref/m/old_atomic/m/$$ $codei%= %ay%.size()%$$, -which must be greater than zero. - -$subhead Parallel Mode$$ -The first call to -$codei% - %afun%(%id%, %ax%, %ay%) -%$$ -must not be in $cref/parallel/ta_in_parallel/$$ mode. -In addition, the -$cref/old_atomic clear/old_atomic/clear/$$ -routine cannot be called while in parallel mode. - -$head forward$$ -The macro argument $icode forward$$ is a -user defined function -$codei% - %ok% = %forward%(%id%, %k%, %n%, %m%, %vx%, %vy%, %tx%, %ty%) -%$$ -that computes results during a $cref/forward/Forward/$$ mode sweep. -For this call, we are given the Taylor coefficients in $icode tx$$ -form order zero through $icode k$$, -and the Taylor coefficients in $icode ty$$ with order less than $icode k$$. -The $icode forward$$ routine computes the -$icode k$$ order Taylor coefficients for $latex y$$ using the definition -$latex Y(t) = f[ X(t) ]$$. -For example, for $latex i = 0 , \ldots , m-1$$, -$latex \[ -\begin{array}{rcl} -y_i^0 & = & Y(0) - = f_i ( x^0 ) -\\ -y_i^1 & = & Y^{(1)} ( 0 ) - = f_i^{(1)} ( x^0 ) X^{(1)} ( 0 ) - = f_i^{(1)} ( x^0 ) x^1 -\\ -y_i^2 -& = & \frac{1}{2 !} Y^{(2)} (0) -\\ -& = & \frac{1}{2} X^{(1)} (0)^\R{T} f_i^{(2)} ( x^0 ) X^{(1)} ( 0 ) - + \frac{1}{2} f_i^{(1)} ( x^0 ) X^{(2)} ( 0 ) -\\ -& = & \frac{1}{2} (x^1)^\R{T} f_i^{(2)} ( x^0 ) x^1 - + f_i^{(1)} ( x^0 ) x^2 -\end{array} -\] $$ -Then, for $latex i = 0 , \ldots , m-1$$, it sets -$latex \[ - ty [ i * (k + 1) + k ] = y_i^k -\] $$ -The other components of $icode ty$$ must be left unchanged. - -$subhead Usage$$ -This routine is used, -with $icode%vx%.size() > 0%$$ and $icode%k% == 0%$$, -by calls to $icode afun$$. -It is used, -with $icode%vx%.size() = 0%$$ and -$icode k$$ equal to the order of the derivative begin computed, -by calls to $cref/forward/forward_order/$$. - -$subhead vx$$ -The $icode forward$$ argument $icode vx$$ has prototype -$codei% - const CppAD::vector& %vx% -%$$ -The case $icode%vx%.size() > 0%$$ occurs -once for each call to $icode afun$$, -during the call, -and before any of the other callbacks corresponding to that call. -Hence such a call can be used to cache information attached to -the corresponding $icode id$$ -(such as the elements of $icode vx$$). -If $icode%vx%.size() > 0%$$ then -$icode%k% == 0%$$, -$icode%vx%.size() >= %n%$$, and -for $latex j = 0 , \ldots , n-1$$, -$icode%vx%[%j%]%$$ is true if and only if -$icode%ax%[%j%]%$$ is a $cref/variable/glossary/Variable/$$. -$pre - -$$ -If $icode%vx%.size() == 0%$$, -then $icode%vy%.size() == 0%$$ and neither of these vectors -should be used. - -$subhead vy$$ -The $icode forward$$ argument $icode vy$$ has prototype -$codei% - CppAD::vector& %vy% -%$$ -If $icode%vy%.size() == 0%$$, it should not be used. -Otherwise, -$icode%k% == 0%$$ and $icode%vy%.size() >= %m%$$. -The input values of the elements of $icode vy$$ -are not specified (must not matter). -Upon return, for $latex j = 0 , \ldots , m-1$$, -$icode%vy%[%i%]%$$ is true if and only if -$icode%ay%[%j%]%$$ is a variable. -(CppAD uses $icode vy$$ to reduce the necessary computations.) - -$head reverse$$ -The macro argument $icode reverse$$ -is a user defined function -$codei% - %ok% = %reverse%(%id%, %k%, %n%, %m%, %tx%, %ty%, %px%, %py%) -%$$ -that computes results during a $cref/reverse/Reverse/$$ mode sweep. -The input value of the vectors $icode tx$$ and $icode ty$$ -contain Taylor coefficient, up to order $icode k$$, -for $latex X(t)$$ and $latex Y(t)$$ respectively. -We use the $latex \{ x_j^\ell \}$$ and $latex \{ y_i^\ell \}$$ -to denote these Taylor coefficients where the implicit range indices are -$latex i = 0 , \ldots , m-1$$, -$latex j = 0 , \ldots , n-1$$, -$latex \ell = 0 , \ldots , k$$. -Using the calculations done by $cref/forward/old_atomic/forward/$$, -the Taylor coefficients $latex \{ y_i^\ell \}$$ are a function of the Taylor -coefficients for $latex \{ x_j^\ell \}$$; i.e., given $latex y = f(x)$$ -we define the function -$latex F : B^{n \times (k+1)} \rightarrow B^{m \times (k+1)}$$ by -$latex \[ -y_i^\ell = F_i^\ell ( \{ x_j^\ell \} ) -\] $$ -We use $latex G : B^{m \times (k+1)} \rightarrow B$$ -to denote an arbitrary scalar valued function of the Taylor coefficients for -$latex Y(t)$$ and write $latex z = G( \{ y_i^\ell \} )$$. -The $code reverse$$ routine -is given the derivative of $latex z$$ with respect to -$latex \{ y_i^\ell \}$$ and computes its derivative with respect -to $latex \{ x_j^\ell \}$$. - -$subhead Usage$$ -This routine is used, -with $icode%k% + 1%$$ equal to the order of the derivative being calculated, -by calls to $cref/reverse/reverse_any/$$. - -$subhead py$$ -The $icode reverse$$ argument $icode py$$ has prototype -$codei% - const CppAD::vector<%Base%>& %py% -%$$ -and $icode%py%.size() >= (%k% + 1) * %m%$$. -For $latex i = 0 , \ldots , m-1$$ and $latex \ell = 0 , \ldots , k$$, -$latex \[ - py[ i * (k + 1 ) + \ell ] = \partial G / \partial y_i^\ell -\] $$ -If $icode%py%.size() > (%k% + 1) * %m%$$, -the other components of $icode py$$ are not specified and should not be used. - -$subhead px$$ -We define the function -$latex \[ -H ( \{ x_j^\ell \} ) = G[ F( \{ x_j^\ell \} ) ] -\] $$ -The $icode reverse$$ argument $icode px$$ has prototype -$codei% - CppAD::vector<%Base%>& %px% -%$$ -and $icode%px%.size() >= (%k% + 1) * %n%$$. -The input values of the elements of $icode px$$ -are not specified (must not matter). -Upon return, -for $latex j = 0 , \ldots , n-1$$ and $latex p = 0 , \ldots , k$$, -$latex \[ -\begin{array}{rcl} -px [ j * (k + 1) + p ] & = & \partial H / \partial x_j^p -\\ -& = & -( \partial G / \partial \{ y_i^\ell \} ) - ( \partial \{ y_i^\ell \} / \partial x_j^p ) -\\ -& = & -\sum_{i=0}^{m-1} \sum_{\ell=0}^k -( \partial G / \partial y_i^\ell ) ( \partial y_i^\ell / \partial x_j^p ) -\\ -& = & -\sum_{i=0}^{m-1} \sum_{\ell=p}^k -py[ i * (k + 1 ) + \ell ] ( \partial F_i^\ell / \partial x_j^p ) -\end{array} -\] $$ -Note that we have used the fact that for $latex \ell < p$$, -$latex \partial F_i^\ell / \partial x_j^p = 0$$. -If $icode%px%.size() > (%k% + 1) * %n%$$, -the other components of $icode px$$ are not specified and should not be used. - -$head for_jac_sparse$$ -The macro argument $icode for_jac_sparse$$ -is a user defined function -$codei% - %ok% = %for_jac_sparse%(%id%, %n%, %m%, %q%, %r%, %s%) -%$$ -that is used to compute results during a forward Jacobian sparsity sweep. -For a fixed $latex n \times q$$ matrix $latex R$$, -the Jacobian of $latex f( x + R * u)$$ with respect to $latex u \in B^q$$ is -$latex \[ - S(x) = f^{(1)} (x) * R -\] $$ -Given a $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for $latex R$$, -$icode for_jac_sparse$$ computes a sparsity pattern for $latex S(x)$$. - -$subhead Usage$$ -This routine is used by calls to $cref ForSparseJac$$. - -$subhead q$$ -The $icode for_jac_sparse$$ argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of columns in -$latex R \in B^{n \times q}$$ and the Jacobian -$latex S(x) \in B^{m \times q}$$. - -$subhead r$$ -The $icode for_jac_sparse$$ argument $icode r$$ has prototype -$codei% - const CppAD::vector< std::set >& %r% -%$$ -and $icode%r%.size() >= %n%$$. -For $latex j = 0 , \ldots , n-1$$, -all the elements of $icode%r%[%j%]%$$ are between -zero and $icode%q%-1%$$ inclusive. -This specifies a sparsity pattern for the matrix $latex R$$. - -$subhead s$$ -The $icode for_jac_sparse$$ return value $icode s$$ has prototype -$codei% - CppAD::vector< std::set >& %s% -%$$ -and $icode%s%.size() >= %m%%$$. -The input values of its sets -are not specified (must not matter). Upon return -for $latex i = 0 , \ldots , m-1$$, -all the elements of $icode%s%[%i%]%$$ are between -zero and $icode%q%-1%$$ inclusive. -This represents a sparsity pattern for the matrix $latex S(x)$$. - -$head rev_jac_sparse$$ -The macro argument $icode rev_jac_sparse$$ -is a user defined function -$codei% - %ok% = %rev_jac_sparse%(%id%, %n%, %m%, %q%, %r%, %s%) -%$$ -that is used to compute results during a reverse Jacobian sparsity sweep. -For a fixed $latex q \times m$$ matrix $latex S$$, -the Jacobian of $latex S * f( x )$$ with respect to $latex x \in B^n$$ is -$latex \[ - R(x) = S * f^{(1)} (x) -\] $$ -Given a $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for $latex S$$, -$icode rev_jac_sparse$$ computes a sparsity pattern for $latex R(x)$$. - -$subhead Usage$$ -This routine is used by calls to $cref RevSparseJac$$ -and to $cref optimize$$. - - -$subhead q$$ -The $icode rev_jac_sparse$$ argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of rows in -$latex S \in B^{q \times m}$$ and the Jacobian -$latex R(x) \in B^{q \times n}$$. - -$subhead s$$ -The $icode rev_jac_sparse$$ argument $icode s$$ has prototype -$codei% - const CppAD::vector< std::set >& %s% -%$$ -and $icode%s%.size() >= %m%$$. -For $latex i = 0 , \ldots , m-1$$, -all the elements of $icode%s%[%i%]%$$ -are between zero and $icode%q%-1%$$ inclusive. -This specifies a sparsity pattern for the matrix $latex S^\R{T}$$. - -$subhead r$$ -The $icode rev_jac_sparse$$ return value $icode r$$ has prototype -$codei% - CppAD::vector< std::set >& %r% -%$$ -and $icode%r%.size() >= %n%$$. -The input values of its sets -are not specified (must not matter). -Upon return for $latex j = 0 , \ldots , n-1$$, -all the elements of $icode%r%[%j%]%$$ -are between zero and $icode%q%-1%$$ inclusive. -This represents a sparsity pattern for the matrix $latex R(x)^\R{T}$$. - -$head rev_hes_sparse$$ -The macro argument $icode rev_hes_sparse$$ -is a user defined function -$codei% - %ok% = %rev_hes_sparse%(%id%, %n%, %m%, %q%, %r%, %s%, %t%, %u%, %v%) -%$$ -There is an unspecified scalar valued function -$latex g : B^m \rightarrow B$$. -Given a sparsity pattern for $latex R$$ -and information about the function $latex z = g(y)$$, -this routine computes the sparsity pattern for -$latex \[ - V(x) = (g \circ f)^{(2)}( x ) R -\] $$ - -$subhead Usage$$ -This routine is used by calls to $cref RevSparseHes$$. - -$subhead q$$ -The $icode rev_hes_sparse$$ argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of columns in the sparsity patterns. - -$subhead r$$ -The $icode rev_hes_sparse$$ argument $icode r$$ has prototype -$codei% - const CppAD::vector< std::set >& %r% -%$$ -and $icode%r%.size() >= %n%$$. -For $latex j = 0 , \ldots , n-1$$, -all the elements of $icode%r%[%j%]%$$ are between -zero and $icode%q%-1%$$ inclusive. -This specifies a sparsity pattern for the matrix $latex R \in B^{n \times q}$$. - -$subhead s$$ -The $icode rev_hes_sparse$$ argument $icode s$$ has prototype -$codei% - const CppAD::vector& %s% -%$$ -and $icode%s%.size() >= %m%$$. -This specifies a sparsity pattern for the matrix -$latex S(x) = g^{(1)} (y) \in B^{1 \times m}$$. - -$subhead t$$ -The $icode rev_hes_sparse$$ argument $icode t$$ has prototype -$codei% - CppAD::vector& %t% -%$$ -and $icode%t%.size() >= %n%$$. -The input values of its elements -are not specified (must not matter). -Upon return it represents a sparsity pattern for the matrix -$latex T(x) \in B^{1 \times n}$$ defined by -$latex \[ -T(x) = (g \circ f)^{(1)} (x) = S(x) * f^{(1)} (x) -\] $$ - -$subhead u$$ -The $icode rev_hes_sparse$$ argument $icode u$$ has prototype -$codei% - const CppAD::vector< std::set >& %u% -%$$ -and $icode%u%.size() >= %m%$$. -For $latex i = 0 , \ldots , m-1$$, -all the elements of $icode%u%[%i%]%$$ -are between zero and $icode%q%-1%$$ inclusive. -This specifies a sparsity pattern -for the matrix $latex U(x) \in B^{m \times q}$$ defined by -$latex \[ -\begin{array}{rcl} -U(x) -& = & -\partial_u \{ \partial_y g[ y + f^{(1)} (x) R u ] \}_{u=0} -\\ -& = & -\partial_u \{ g^{(1)} [ y + f^{(1)} (x) R u ] \}_{u=0} -\\ -& = & -g^{(2)} (y) f^{(1)} (x) R -\end{array} -\] $$ - -$subhead v$$ -The $icode rev_hes_sparse$$ argument $icode v$$ has prototype -$codei% - CppAD::vector< std::set >& %v% -%$$ -and $icode%v%.size() >= %n%$$. -The input values of its elements -are not specified (must not matter). -Upon return, for $latex j = 0, \ldots , n-1$$, -all the elements of $icode%v%[%j%]%$$ -are between zero and $icode%q%-1%$$ inclusive. -This represents a sparsity pattern for the matrix -$latex V(x) \in B^{n \times q}$$ defined by -$latex \[ -\begin{array}{rcl} -V(x) -& = & -\partial_u [ \partial_x (g \circ f) ( x + R u ) ]_{u=0} -\\ -& = & -\partial_u [ (g \circ f)^{(1)}( x + R u ) ]_{u=0} -\\ -& = & -(g \circ f)^{(2)}( x ) R -\\ -& = & -f^{(1)} (x)^\R{T} g^{(2)} ( y ) f^{(1)} (x) R -+ -\sum_{i=1}^m [ g^{(1)} (y) ]_i \; f_i^{(2)} (x) R -\\ -& = & -f^{(1)} (x)^\R{T} U(x) -+ -\sum_{i=1}^m S(x)_i \; f_i^{(2)} (x) R -\end{array} -\] $$ - -$head clear$$ -User atomic functions hold onto static work space in order to -increase speed by avoiding system memory allocation calls. -The function call $codei% - user_atomic<%Base%>::clear() -%$$ -makes to work space $cref/available/ta_available/$$ to -for other uses by the same thread. -This should be called when you are done using the -user atomic functions for a specific value of $icode Base$$. - -$subhead Restriction$$ -The user atomic $code clear$$ routine cannot be called -while in $cref/parallel/ta_in_parallel/$$ execution mode. - -$children% - test_more/old_reciprocal.cpp% - test_more/old_usead_1.cpp% - test_more/old_usead_2.cpp% - test_more/old_tan.cpp% - test_more/old_mat_mul.cpp -%$$ -$head Example$$ - -$subhead Simple$$ -The file $cref old_reciprocal.cpp$$ contains the simplest example and test -of a user atomic operation. - -$subhead Use AD$$ -The examples -$cref old_usead_1.cpp$$ and $cref old_usead_2.cpp$$ -use AD to compute the derivatives -inside a user defined atomic function. -This may have the advantage of reducing the size of the tape, because -a repeated section of code would only be taped once. - -$subhead Tangent Function$$ -The file $cref old_tan.cpp$$ contains an example and test -implementation of the tangent function as a user atomic operation. - -$subhead Matrix Multiplication$$ -The file $cref old_mat_mul.cpp$$ contains an example and test -implementation of matrix multiplication a a user atomic operation. - -$end ------------------------------------------------------------------------------- -*/ -# include -# include - -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file old_atomic.hpp -user defined atomic operations. -*/ - -/*! -\def CPPAD_USER_ATOMIC(afun, Tvector, - forward, reverse, for_jac_sparse, rev_jac_sparse, rev_hes_sparse -) -Defines the function afun(id, ax, ay) -where \c id is \c ax and \c ay are vectors with AD elements. - -\par Tvector -the Simple Vector template class for this function. - -\par Base -the base type for the atomic operation. - -\par afun -name of the CppAD defined function that corresponding to this operation. -Note that \c afun, preceeded by a pound sign, -is a version of \c afun with quotes arround it. - -\par forward -name of the user defined function that computes corresponding -results during forward mode. - -\par reverse -name of the user defined function that computes corresponding -results during reverse mode. - -\par for_jac_sparse -name of the user defined routine that computes corresponding -results during forward mode jacobian sparsity sweeps. - -\par rev_jac_sparse -name of the user defined routine that computes corresponding -results during reverse mode jacobian sparsity sweeps. - -\par rev_hes_sparse -name of the user defined routine that computes corresponding -results during reverse mode Hessian sparsity sweeps. - -\par memory allocation -Note that old_atomic is used as a static object, so its objects -do note get deallocated until the program terminates. -*/ -# define CPPAD_USER_ATOMIC( \ - afun , \ - Tvector , \ - Base , \ - forward , \ - reverse , \ - for_jac_sparse , \ - rev_jac_sparse , \ - rev_hes_sparse \ -) \ -inline void afun ( \ - size_t id , \ - const Tvector< CppAD::AD >& ax , \ - Tvector< CppAD::AD >& ay \ -) \ -{ CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; \ - static CppAD::old_atomic fun( \ - #afun , \ - forward , \ - reverse , \ - for_jac_sparse , \ - rev_jac_sparse , \ - rev_hes_sparse \ - ); \ - fun(id, ax, ay); \ -} - -/// link so that user_atomic::clear() still works -template class user_atomic : public atomic_base { -}; - -/*! -Class that actually implements the afun(id, ax, ay) calls. - -A new old_atomic object is generated each time the user invokes -the CPPAD_USER_ATOMIC macro; see static object in that macro. -*/ -template -class old_atomic : public atomic_base { -public: - /// disable old_atomic::clear(void) - static void clear(void) - { CPPAD_ASSERT_KNOWN( - false, - "Depreacted API uses user_atomic::clear()" - ); - } - /// type for user routine that computes forward mode results - typedef bool (*F) ( - size_t id , - size_t k , - size_t n , - size_t m , - const vector& vx , - vector& vy , - const vector& tx , - vector& ty - ); - /// type for user routine that computes reverse mode results - typedef bool (*R) ( - size_t id , - size_t k , - size_t n , - size_t m , - const vector& tx , - const vector& ty , - vector& px , - const vector& py - ); - /// type for user routine that computes forward mode Jacobian sparsity - typedef bool (*FJS) ( - size_t id , - size_t n , - size_t m , - size_t q , - const vector< std::set >& r , - vector< std::set >& s - ); - /// type for user routine that computes reverse mode Jacobian sparsity - typedef bool (*RJS) ( - size_t id , - size_t n , - size_t m , - size_t q , - vector< std::set >& r , - const vector< std::set >& s - ); - /// type for user routine that computes reverse mode Hessian sparsity - typedef bool (*RHS) ( - size_t id , - size_t n , - size_t m , - size_t q , - const vector< std::set >& r , - const vector& s , - vector& t , - const vector< std::set >& u , - vector< std::set >& v - ); -private: - /// id value corresponding to next virtual callback - size_t id_; - /// user's implementation of forward mode - const F f_; - /// user's implementation of reverse mode - const R r_; - /// user's implementation of forward jacobian sparsity calculations - const FJS fjs_; - /// user's implementation of reverse jacobian sparsity calculations - const RJS rjs_; - /// user's implementation of reverse Hessian sparsity calculations - const RHS rhs_; - -public: - /*! - Constructor called for each invocation of CPPAD_USER_ATOMIC. - - Put this object in the list of all objects for this class and set - the constant private data f_, r_, fjs_, rjs_, rhs_. - - \param afun - is the user's name for the AD version of this atomic operation. - - \param f - user routine that does forward mode calculations for this operation. - - \param r - user routine that does reverse mode calculations for this operation. - - \param fjs - user routine that does forward Jacobian sparsity calculations. - - \param rjs - user routine that does reverse Jacobian sparsity calculations. - - \param rhs - user routine that does reverse Hessian sparsity calculations. - - \par - This constructor can not be used in parallel mode because - atomic_base has this restriction. - */ - old_atomic(const char* afun, F f, R r, FJS fjs, RJS rjs, RHS rhs) : - atomic_base(afun) // name = afun - , f_(f) - , r_(r) - , fjs_(fjs) - , rjs_(rjs) - , rhs_(rhs) - { this->option( atomic_base::set_sparsity_enum ); - } - /*! - Implement the user call to afun(id, ax, ay). - - \tparam ADVector - A simple vector class with elements of type AD. - - \param id - extra information vector that is just passed through by CppAD, - and possibly used by user's routines. - - \param ax - is the argument vector for this call, - ax.size() determines the number of arguments. - - \param ay - is the result vector for this call, - ay.size() determines the number of results. - */ - template - void operator()(size_t id, const ADVector& ax, ADVector& ay) - { // call atomic_base function object - this->atomic_base::operator()(ax, ay, id); - return; - } - /*! - Store id for next virtual function callback - - \param id - id value corresponding to next virtual callback - */ - virtual void set_old(size_t id) - { id_ = id; } - /*! - Link from old_atomic to forward mode - - \copydetails atomic_base::forward - */ - virtual bool forward( - size_t p , - size_t q , - const vector& vx , - vector& vy , - const vector& tx , - vector& ty ) - { CPPAD_ASSERT_UNKNOWN( tx.size() % (q+1) == 0 ); - CPPAD_ASSERT_UNKNOWN( ty.size() % (q+1) == 0 ); - size_t n = tx.size() / (q+1); - size_t m = ty.size() / (q+1); - size_t i, j, k, ell; - - vector x(n * (q+1)); - vector y(m * (q+1)); - vector empty; - - // old_atomic interface can only handel one order at a time - // so must just throuh hoops to get multiple orders at one time. - bool ok = true; - for(k = p; k <= q; k++) - { for(j = 0; j < n; j++) - for(ell = 0; ell <= k; ell++) - x[ j * (k+1) + ell ] = tx[ j * (q+1) + ell ]; - for(i = 0; i < m; i++) - for(ell = 0; ell < k; ell++) - y[ i * (k+1) + ell ] = ty[ i * (q+1) + ell ]; - if( k == 0 ) - ok &= f_(id_, k, n, m, vx, vy, x, y); - else - ok &= f_(id_, k, n, m, empty, empty, x, y); - for(i = 0; i < m; i++) - ty[ i * (q+1) + k ] = y[ i * (k+1) + k]; - } - return ok; - } - /*! - Link from old_atomic to reverse mode - - \copydetails atomic_base::reverse - */ - virtual bool reverse( - size_t q , - const vector& tx , - const vector& ty , - vector& px , - const vector& py ) - { CPPAD_ASSERT_UNKNOWN( tx.size() % (q+1) == 0 ); - CPPAD_ASSERT_UNKNOWN( ty.size() % (q+1) == 0 ); - size_t n = tx.size() / (q+1); - size_t m = ty.size() / (q+1); - bool ok = r_(id_, q, n, m, tx, ty, px, py); - return ok; - } - /*! - Link from forward Jacobian sparsity sweep to old_atomic - - \copydetails atomic_base::for_sparse_jac - */ - virtual bool for_sparse_jac( - size_t q , - const vector< std::set >& r , - vector< std::set >& s , - const vector& x ) - { size_t n = r.size(); - size_t m = s.size(); - bool ok = fjs_(id_, n, m, q, r, s); - return ok; - } - - /*! - Link from reverse Jacobian sparsity sweep to old_atomic. - - \copydetails atomic_base::rev_sparse_jac - */ - virtual bool rev_sparse_jac( - size_t q , - const vector< std::set >& rt , - vector< std::set >& st , - const vector& x ) - { size_t n = st.size(); - size_t m = rt.size(); - bool ok = rjs_(id_, n, m, q, st, rt); - return ok; - } - /*! - Link from reverse Hessian sparsity sweep to old_atomic - - \copydetails atomic_base::rev_sparse_hes - */ - virtual bool rev_sparse_hes( - const vector& vx, - const vector& s , - vector& t , - size_t q , - const vector< std::set >& r , - const vector< std::set >& u , - vector< std::set >& v , - const vector& x ) - { size_t m = u.size(); - size_t n = v.size(); - CPPAD_ASSERT_UNKNOWN( r.size() == n ); - CPPAD_ASSERT_UNKNOWN( s.size() == m ); - CPPAD_ASSERT_UNKNOWN( t.size() == n ); - // - // old interface used id instead of vx - bool ok = rhs_(id_, n, m, q, r, s, t, u, v); - return ok; - } -}; - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/omp_max_thread.hpp b/ct_core/include/ct/external/cppad/core/omp_max_thread.hpp deleted file mode 100644 index 134bab745..000000000 --- a/ct_core/include/ct/external/cppad/core/omp_max_thread.hpp +++ /dev/null @@ -1,95 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_OMP_MAX_THREAD_HPP -# define CPPAD_CORE_OMP_MAX_THREAD_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin omp_max_thread$$ -$spell - alloc - num - omp - OpenMp - CppAD -$$ - -$section OpenMP Parallel Setup$$ -$mindex omp_max_thread$$ - -$head Deprecated 2011-06-23$$ -Use $cref/thread_alloc::parallel_setup/ta_parallel_setup/$$ -to set the number of threads. - -$head Syntax$$ -$codei%AD<%Base%>::omp_max_thread(%number%) -%$$ - -$head Purpose$$ -By default, for each $codei%AD<%Base%>%$$ class there is only one -tape that records $cref/AD of Base/glossary/AD of Base/$$ operations. -This tape is a global variable and hence it cannot be used -by multiple OpenMP threads at the same time. -The $code omp_max_thread$$ function is used to set the -maximum number of OpenMP threads that can be active. -In this case, there is a different tape corresponding to each -$codei%AD<%Base%>%$$ class and thread pair. - -$head number$$ -The argument $icode number$$ has prototype -$codei% - size_t %number% -%$$ -It must be greater than zero and specifies the maximum number of -OpenMp threads that will be active at one time. - - -$head Independent$$ -Each call to $cref/Independent(x)/Independent/$$ -creates a new $cref/active/glossary/Tape/Active/$$ tape. -All of the operations with the corresponding variables -must be preformed by the same OpenMP thread. -This includes the corresponding call to -$cref/f.Dependent(x,y)/Dependent/$$ or the -$cref/ADFun f(x, y)/FunConstruct/Sequence Constructor/$$ -during which the tape stops recording and the variables -become parameters. - -$head Restriction$$ -No tapes can be -$cref/active/glossary/Tape/Active/$$ when this function is called. - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -void AD::omp_max_thread(size_t number) -{ -# ifdef _OPENMP - thread_alloc::parallel_setup( - number, omp_alloc::in_parallel, omp_alloc::get_thread_num - ); -# else - CPPAD_ASSERT_KNOWN( - number == 1, - "omp_max_thread: number > 1 and _OPENMP is not defined" - ); -# endif - parallel_ad(); -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/opt_val_hes.hpp b/ct_core/include/ct/external/cppad/core/opt_val_hes.hpp deleted file mode 100644 index ad181201c..000000000 --- a/ct_core/include/ct/external/cppad/core/opt_val_hes.hpp +++ /dev/null @@ -1,525 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_OPT_VAL_HES_HPP -# define CPPAD_CORE_OPT_VAL_HES_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin opt_val_hes$$ -$spell - hes - sy - Jacobian - hes - signdet - jac - Bradley - const - CppAD -$$ - - - -$section Jacobian and Hessian of Optimal Values$$ -$mindex opt_val_hes$$ - -$head Syntax$$ -$icode%signdet% = opt_val_hes(%x%, %y%, %fun%, %jac%, %hes%)%$$ - -$head See Also$$ -$cref BenderQuad$$ - -$head Reference$$ -Algorithmic differentiation of implicit functions and optimal values, -Bradley M. Bell and James V. Burke, Advances in Automatic Differentiation, -2008, Springer. - -$head Purpose$$ -We are given a function -$latex S : \B{R}^n \times \B{R}^m \rightarrow \B{R}^\ell$$ -and we define $latex F : \B{R}^n \times \B{R}^m \rightarrow \B{R}$$ -and $latex V : \B{R}^n \rightarrow \B{R} $$ by -$latex \[ -\begin{array}{rcl} - F(x, y) & = & \sum_{k=0}^{\ell-1} S_k ( x , y) - \\ - V(x) & = & F [ x , Y(x) ] - \\ - 0 & = & \partial_y F [x , Y(x) ] -\end{array} -\] $$ -We wish to compute the Jacobian -and possibly also the Hessian, of $latex V (x)$$. - -$head BaseVector$$ -The type $icode BaseVector$$ must be a -$cref SimpleVector$$ class. -We use $icode Base$$ to refer to the type of the elements of -$icode BaseVector$$; i.e., -$codei% - %BaseVector%::value_type -%$$ - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %BaseVector%& %x% -%$$ -and its size must be equal to $icode n$$. -It specifies the point at which we evaluating -the Jacobian $latex V^{(1)} (x)$$ -(and possibly the Hessian $latex V^{(2)} (x)$$). - - -$head y$$ -The argument $icode y$$ has prototype -$codei% - const %BaseVector%& %y% -%$$ -and its size must be equal to $icode m$$. -It must be equal to $latex Y(x)$$; i.e., -it must solve the implicit equation -$latex \[ - 0 = \partial_y F ( x , y) -\] $$ - -$head Fun$$ -The argument $icode fun$$ is an object of type $icode Fun$$ -which must support the member functions listed below. -CppAD will may be recording operations of the type $codei%AD<%Base%>%$$ -when these member functions are called. -These member functions must not stop such a recording; e.g., -they must not call $cref/AD::abort_recording/abort_recording/$$. - -$subhead Fun::ad_vector$$ -The type $icode%Fun%::ad_vector%$$ must be a -$cref SimpleVector$$ class with elements of type $codei%AD<%Base%>%$$; i.e. -$codei% - %Fun%::ad_vector::value_type -%$$ -is equal to $codei%AD<%Base%>%$$. - -$subhead fun.ell$$ -The type $icode Fun$$ must support the syntax -$codei% - %ell% = %fun%.ell() -%$$ -where $icode ell$$ has prototype -$codei% - size_t %ell% -%$$ -and is the value of $latex \ell$$; i.e., -the number of terms in the summation. -$pre - -$$ -One can choose $icode ell$$ equal to one, and have -$latex S(x,y)$$ the same as $latex F(x, y)$$. -Each of the functions $latex S_k (x , y)$$, -(in the summation defining $latex F(x, y)$$) -is differentiated separately using AD. -For very large problems, breaking $latex F(x, y)$$ into the sum -of separate simpler functions may reduce the amount of memory necessary for -algorithmic differentiation and there by speed up the process. - -$subhead fun.s$$ -The type $icode Fun$$ must support the syntax -$codei% - %s_k% = %fun%.s(%k%, %x%, %y%) -%$$ -The $icode%fun%.s%$$ argument $icode k$$ has prototype -$codei% - size_t %k% -%$$ -and is between zero and $icode%ell% - 1%$$. -The argument $icode x$$ to $icode%fun%.s%$$ has prototype -$codei% - const %Fun%::ad_vector& %x% -%$$ -and its size must be equal to $icode n$$. -The argument $icode y$$ to $icode%fun%.s%$$ has prototype -$codei% - const %Fun%::ad_vector& %y% -%$$ -and its size must be equal to $icode m$$. -The $icode%fun%.s%$$ result $icode s_k$$ has prototype -$codei% - AD<%Base%> %s_k% -%$$ -and its value must be given by $latex s_k = S_k ( x , y )$$. - -$subhead fun.sy$$ -The type $icode Fun$$ must support the syntax -$codei% - %sy_k% = %fun%.sy(%k%, %x%, %y%) -%$$ -The argument $icode k$$ to $icode%fun%.sy%$$ has prototype -$codei% - size_t %k% -%$$ -The argument $icode x$$ to $icode%fun%.sy%$$ has prototype -$codei% - const %Fun%::ad_vector& %x% -%$$ -and its size must be equal to $icode n$$. -The argument $icode y$$ to $icode%fun%.sy%$$ has prototype -$codei% - const %Fun%::ad_vector& %y% -%$$ -and its size must be equal to $icode m$$. -The $icode%fun%.sy%$$ result $icode sy_k$$ has prototype -$codei% - %Fun%::ad_vector %sy_k% -%$$ -its size must be equal to $icode m$$, -and its value must be given by $latex sy_k = \partial_y S_k ( x , y )$$. - -$head jac$$ -The argument $icode jac$$ has prototype -$codei% - %BaseVector%& %jac% -%$$ -and has size $icode n$$ or zero. -The input values of its elements do not matter. -If it has size zero, it is not affected. Otherwise, on output -it contains the Jacobian of $latex V (x)$$; i.e., -for $latex j = 0 , \ldots , n-1$$, -$latex \[ - jac[ j ] = V^{(1)} (x)_j -\] $$ -where $icode x$$ is the first argument to $code opt_val_hes$$. - -$head hes$$ -The argument $icode hes$$ has prototype -$codei% - %BaseVector%& %hes% -%$$ -and has size $icode%n% * %n%$$ or zero. -The input values of its elements do not matter. -If it has size zero, it is not affected. Otherwise, on output -it contains the Hessian of $latex V (x)$$; i.e., -for $latex i = 0 , \ldots , n-1$$, and -$latex j = 0 , \ldots , n-1$$, -$latex \[ - hes[ i * n + j ] = V^{(2)} (x)_{i,j} -\] $$ - - -$head signdet$$ -If $icode%hes%$$ has size zero, $icode signdet$$ is not defined. -Otherwise -the return value $icode signdet$$ is the sign of the determinant for -$latex \partial_{yy}^2 F(x , y) $$. -If it is zero, then the matrix is singular and -the Hessian is not computed ($icode hes$$ is not changed). - -$head Example$$ -$children% - example/opt_val_hes.cpp -%$$ -The file -$cref opt_val_hes.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file opt_val_hes.hpp -\brief Computing Jabobians and Hessians of Optimal Values -*/ - -/*! -Computing Jabobians and Hessians of Optimal Values - -We are given a function -\f$ S : {\rm R}^n \times {\rm R}^m \rightarrow {\rm R}^\ell \f$ -and we define \f$ F : {\rm R}^n \times {\rm R}^m \rightarrow {\rm R} \f$ -and \f$ V : {\rm R}^n \rightarrow {\rm R} \f$ by -\f[ -\begin{array}{rcl} - F(x, y) & = & \sum_{k=0}^{\ell-1} S_k ( x , y) - \\ - V(x) & = & F [ x , Y(x) ] - \\ - 0 & = & \partial_y F [x , Y(x) ] -\end{array} -\f] -We wish to compute the Jacobian -and possibly also the Hessian, of \f$ V (x) \f$. - -\tparam BaseVector -The type \c BaseVector must be a SimpleVector class. -We use \c Base to refer to the type of the elements of -\c BaseVector; i.e., -BaseVector::value_type. - -\param x -is a vector with size \c n. -It specifies the point at which we evaluating -the Jacobian \f$ V^{(1)} (x) \f$ -(and possibly the Hessian \f$ V^{(2)} (x) \f$). - - -\param y -is a vector with size \c m. -It must be equal to \f$ Y(x) \f$; i.e., -it must solve the implicit equation -\f[ - 0 = \partial_y F ( x , y) -\f] - -\param fun -The argument \c fun is an object of type \c Fun -wich must support the member functions listed below. -CppAD will may be recording operations of the type \c AD -when these member functions are called. -These member functions must not stop such a recording; e.g., -they must not call \c AD::abort_recording. - -\par Fun::ad_vector -The type Fun::ad_vector must be a -SimpleVector class with elements of type \c AD; i.e. -Fun::ad_vector::value_type -is equal to \c AD. - -\par fun.ell -the type \c Fun must support the syntax -\verbatim - ell = fun.ell() -\endverbatim -where \c ell is a \c size_t value that is set to \f$ \ell \f$; i.e., -the number of terms in the summation. - -\par fun.s -The type \c Fun must support the syntax -\verbatim - s_k = fun.s(k, x, y) -\endverbatim -The argument \c k has prototype size_t k. -The argument \c x has prototype const Fun::ad_vector& x -and its size must be equal to \c n. -The argument \c y has prototype const Fun::ad_vector& y -and its size must be equal to \c m. -The return value \c s_k has prototype \c AD s_k -and its value must be given by \f$ s_k = S_k ( x , y ) \f$. - -\par fun.sy -The type \c Fun must support the syntax -\verbatim - sy_k = fun.sy(k, x, y) -\endverbatim -The argument \c k has prototype size_t k. -The argument \c x has prototype const Fun::ad_vector& x -and its size must be equal to \c n. -The argument \c y has prototype const Fun::ad_vector& y -and its size must be equal to \c m. -The return value \c sy_k has prototype Fun::ad_vector& sy_k, -its size is \c m -and its value must be given by \f$ sy_k = \partial_y S_k ( x , y ) \f$. - -\param jac -is a vector with size \c n or zero. -The input values of its elements do not matter. -If it has size zero, it is not affected. Otherwise, on output -it contains the Jacobian of \f$ V (x) \f$; i.e., -for \f$ j = 0 , \ldots , n-1 \f$, -\f[ - jac[ j ] = V^{(1)} (x)_j -\f] $$ -where \c x is the first argument to \c opt_val_hes. - -\param hes -is a vector with size n * n or zero. -The input values of its elements do not matter. -If it has size zero, it is not affected. Otherwise, on output -it contains the Hessian of \f$ V (x) \f$; i.e., -for \f$ i = 0 , \ldots , n-1 \f$, and -\f$ j = 0 , \ldots , n-1 \f$, -\f[ - hes[ i * n + j ] = V^{(2)} (x)_{i,j} -\f] - -\return -If hes.size() == 0, the return value is not defined. -Otherwise, -the return value is the sign of the determinant for -\f$ \partial_{yy}^2 F(x , y) \f$$. -If it is zero, then the matrix is singular and \c hes is not set -to its specified value. -*/ - - -template -int opt_val_hes( - const BaseVector& x , - const BaseVector& y , - Fun fun , - BaseVector& jac , - BaseVector& hes ) -{ // determine the base type - typedef typename BaseVector::value_type Base; - - // check that BaseVector is a SimpleVector class with Base elements - CheckSimpleVector(); - - // determine the AD vector type - typedef typename Fun::ad_vector ad_vector; - - // check that ad_vector is a SimpleVector class with AD elements - CheckSimpleVector< AD , ad_vector >(); - - // size of the x and y spaces - size_t n = size_t(x.size()); - size_t m = size_t(y.size()); - - // number of terms in the summation - size_t ell = fun.ell(); - - // check size of return values - CPPAD_ASSERT_KNOWN( - size_t(jac.size()) == n || jac.size() == 0, - "opt_val_hes: size of the vector jac is not equal to n or zero" - ); - CPPAD_ASSERT_KNOWN( - size_t(hes.size()) == n * n || hes.size() == 0, - "opt_val_hes: size of the vector hes is not equal to n * n or zero" - ); - - // some temporary indices - size_t i, j, k; - - // AD version of S_k(x, y) - ad_vector s_k(1); - - // ADFun version of S_k(x, y) - ADFun S_k; - - // AD version of x - ad_vector a_x(n); - - // AD version of y - ad_vector a_y(n); - - if( jac.size() > 0 ) - { // this is the easy part, computing the V^{(1)} (x) which is equal - // to \partial_x F (x, y) (see Thoerem 2 of the reference). - - // copy x and y to AD version - for(j = 0; j < n; j++) - a_x[j] = x[j]; - for(j = 0; j < m; j++) - a_y[j] = y[j]; - - // initialize summation - for(j = 0; j < n; j++) - jac[j] = Base(0.); - - // add in \partial_x S_k (x, y) - for(k = 0; k < ell; k++) - { // start recording - Independent(a_x); - // record - s_k[0] = fun.s(k, a_x, a_y); - // stop recording and store in S_k - S_k.Dependent(a_x, s_k); - // compute partial of S_k with respect to x - BaseVector jac_k = S_k.Jacobian(x); - // add \partial_x S_k (x, y) to jac - for(j = 0; j < n; j++) - jac[j] += jac_k[j]; - } - } - // check if we are done - if( hes.size() == 0 ) - return 0; - - /* - In this case, we need to compute the Hessian. Using Theorem 1 of the - reference: - Y^{(1)}(x) = - F_yy (x, y)^{-1} F_yx (x, y) - Using Theorem 2 of the reference: - V^{(2)}(x) = F_xx (x, y) + F_xy (x, y) Y^{(1)}(x) - */ - // Base and AD version of xy - BaseVector xy(n + m); - ad_vector a_xy(n + m); - for(j = 0; j < n; j++) - a_xy[j] = xy[j] = x[j]; - for(j = 0; j < m; j++) - a_xy[n+j] = xy[n+j] = y[j]; - - // Initialization summation for Hessian of F - size_t nm_sq = (n + m) * (n + m); - BaseVector F_hes(nm_sq); - for(j = 0; j < nm_sq; j++) - F_hes[j] = Base(0.); - BaseVector hes_k(nm_sq); - - // add in Hessian of S_k to hes - for(k = 0; k < ell; k++) - { // start recording - Independent(a_xy); - // split out x - for(j = 0; j < n; j++) - a_x[j] = a_xy[j]; - // split out y - for(j = 0; j < m; j++) - a_y[j] = a_xy[n+j]; - // record - s_k[0] = fun.s(k, a_x, a_y); - // stop recording and store in S_k - S_k.Dependent(a_xy, s_k); - // when computing the Hessian it pays to optimize the tape - S_k.optimize(); - // compute Hessian of S_k - hes_k = S_k.Hessian(xy, 0); - // add \partial_x S_k (x, y) to jac - for(j = 0; j < nm_sq; j++) - F_hes[j] += hes_k[j]; - } - // Extract F_yx - BaseVector F_yx(m * n); - for(i = 0; i < m; i++) - { for(j = 0; j < n; j++) - F_yx[i * n + j] = F_hes[ (i+n)*(n+m) + j ]; - } - // Extract F_yy - BaseVector F_yy(n * m); - for(i = 0; i < m; i++) - { for(j = 0; j < m; j++) - F_yy[i * m + j] = F_hes[ (i+n)*(n+m) + j + n ]; - } - - // compute - Y^{(1)}(x) = F_yy (x, y)^{-1} F_yx (x, y) - BaseVector neg_Y_x(m * n); - Base logdet; - int signdet = CppAD::LuSolve(m, n, F_yy, F_yx, neg_Y_x, logdet); - if( signdet == 0 ) - return signdet; - - // compute hes = F_xx (x, y) + F_xy (x, y) Y^{(1)}(x) - for(i = 0; i < n; i++) - { for(j = 0; j < n; j++) - { hes[i * n + j] = F_hes[ i*(n+m) + j ]; - for(k = 0; k < m; k++) - hes[i*n+j] -= F_hes[i*(n+m) + k+n] * neg_Y_x[k*n+j]; - } - } - return signdet; -} - -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/core/optimize.hpp b/ct_core/include/ct/external/cppad/core/optimize.hpp deleted file mode 100644 index 872e32aa9..000000000 --- a/ct_core/include/ct/external/cppad/core/optimize.hpp +++ /dev/null @@ -1,298 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_OPTIMIZE_HPP -# define CPPAD_CORE_OPTIMIZE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin optimize$$ -$spell - enum - jac - bool - Taylor - CppAD - cppad - std - const - onetape - op -$$ - -$section Optimize an ADFun Object Tape$$ -$mindex sequence operations speed memory NDEBUG$$ - - -$head Syntax$$ -$icode%f%.optimize() -%$$ -$icode%f%.optimize(%options%) -%$$ - -$head Purpose$$ -The operation sequence corresponding to an $cref ADFun$$ object can -be very large and involve many operations; see the -size functions in $cref seq_property$$. -The $icode%f%.optimize%$$ procedure reduces the number of operations, -and thereby the time and the memory, required to -compute function and derivative values. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ - -$head options$$ -This argument has prototype -$codei% - const std::string& %options% -%$$ -The default for $icode options$$ is the empty string. -If it is present, it must consist of one or more of the options below -separated by a single space character. - -$subhead no_conditional_skip$$ -The $code optimize$$ function can create conditional skip operators -to improve the speed of conditional expressions; see -$cref/optimize/CondExp/Optimize/$$. -If the sub-string $code no_conditional_skip$$ appears in $icode options$$, -conditional skip operations are not be generated. -This may make the optimize routine use significantly less memory -and take less time to optimize $icode f$$. -If conditional skip operations are generated, -it may save a significant amount of time when -using $icode f$$ for $cref forward$$ or $cref reverse$$ mode calculations; -see $cref number_skip$$. - -$subhead no_compare_op$$ -If the sub-string $code no_compare_op$$ appears in $icode options$$, -comparison operators will be removed from the optimized function. -These operators are necessary for the -$cref compare_change$$ functions to be meaningful. -On the other hand, they are not necessary, and take extra time, -when the compare_change functions are not used. - -$subhead no_print_for_op$$ -If the sub-string $code no_compare_op$$ appears in $icode options$$, -$cref PrintFor$$ operations will be removed form the optimized function. -These operators are useful for reporting problems evaluating derivatives -at independent variable values different from those used to record a function. - -$head Examples$$ -$children% - example/optimize/forward_active.cpp - %example/optimize/reverse_active.cpp - %example/optimize/compare_op.cpp - %example/optimize/print_for.cpp - %example/optimize/conditional_skip.cpp - %example/optimize/nest_conditional.cpp - %example/optimize/cumulative_sum.cpp -%$$ -$table -$cref/forward_active.cpp/optimize_forward_active.cpp/$$ $cnext - $title optimize_forward_active.cpp$$ -$rnext -$cref/reverse_active.cpp/optimize_reverse_active.cpp/$$ $cnext - $title optimize_reverse_active.cpp$$ -$rnext -$cref/compare_op.cpp/optimize_compare_op.cpp/$$ $cnext - $title optimize_compare_op.cpp$$ -$rnext -$cref/print_for_op.cpp/optimize_print_for.cpp/$$ $cnext - $title optimize_print_for.cpp$$ -$rnext -$cref/conditional_skip.cpp/optimize_conditional_skip.cpp/$$ $cnext - $title optimize_conditional_skip.cpp$$ -$rnext -$cref/nest_conditional.cpp/optimize_nest_conditional.cpp/$$ $cnext - $title optimize_nest_conditional.cpp$$ -$rnext -$cref/cumulative_sum.cpp/optimize_cumulative_sum.cpp/$$ $cnext - $title optimize_cumulative_sum.cpp$$ -$tend - -$head Efficiency$$ -If a $cref/zero order forward/forward_zero/$$ calculation is done during -the construction of $icode f$$, it will require more memory -and time than required after the optimization procedure. -In addition, it will need to be redone. -For this reason, it is more efficient to use -$codei% - ADFun<%Base%> %f%; - %f%.Dependent(%x%, %y%); - %f%.optimize(); -%$$ -instead of -$codei% - ADFun<%Base%> %f%(%x%, %y%) - %f%.optimize(); -%$$ -See the discussion about -$cref/sequence constructors/FunConstruct/Sequence Constructor/$$. - -$head Speed Testing$$ -You can run the CppAD $cref/speed/speed_main/$$ tests and see -the corresponding changes in number of variables and execution time. -Note that there is an interaction between using -$cref/optimize/speed_main/Global Options/optimize/$$ and -$cref/onetape/speed_main/Global Options/onetape/$$. -If $icode onetape$$ is true and $icode optimize$$ is true, -the optimized tape will be reused many times. -If $icode onetape$$ is false and $icode optimize$$ is true, -the tape will be re-optimized for each test. - -$head Atomic Functions$$ -There are some subtitle issue with optimized $cref atomic$$ functions -$latex v = g(u)$$: - -$subhead rev_sparse_jac$$ -The $cref atomic_rev_sparse_jac$$ function is be used to determine -which components of $icode u$$ affect the dependent variables of $icode f$$. -For each atomic operation, the current -$cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ setting is used -to determine if $code pack_sparsity_enum$$, $code bool_sparsity_enum$$, -or $code set_sparsity_enum$$ is used to determine dependency relations -between argument and result variables. - -$subhead nan$$ -If $icode%u%[%i%]%$$ does not affect the value of -the dependent variables for $icode f$$, -the value of $icode%u%[%i%]%$$ is set to $cref nan$$. - -$head Checking Optimization$$ -If $cref/NDEBUG/Faq/Speed/NDEBUG/$$ is not defined, -and $cref/f.size_order()/size_order/$$ is greater than zero, -a $cref forward_zero$$ calculation is done using the optimized version -of $icode f$$ and the results are checked to see that they are -the same as before. -If they are not the same, the -$cref ErrorHandler$$ is called with a known error message -related to $icode%f%.optimize()%$$. - -$end ------------------------------------------------------------------------------ -*/ -# include -/*! -\file optimize.hpp -Optimize a player object operation sequence -*/ -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -Optimize a player object operation sequence - -The operation sequence for this object is replaced by one with fewer operations -but the same funcition and derivative values. - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD and computations by this routine are done using type -\a Base. - -\param options -\li -If the sub-string "no_conditional_skip" appears, -conditional skip operations will not be generated. -This may make the optimize routine use significantly less memory -and take significantly less time. -\li -If the sub-string "no_compare_op" appears, -then comparison operators will be removed from the optimized tape. -These operators are necessary for the compare_change function to be -be meaningful in the resulting recording. -On the other hand, they are not necessary and take extra time -when compare_change is not used. -*/ -template -void ADFun::optimize(const std::string& options) -{ // place to store the optimized version of the recording - local::recorder rec; - - // number of independent variables - size_t n = ind_taddr_.size(); - -# ifndef NDEBUG - size_t i, j, m = dep_taddr_.size(); - CppAD::vector x(n), y(m), check(m); - Base max_taylor(0); - bool check_zero_order = num_order_taylor_ > 0; - if( check_zero_order ) - { // zero order coefficients for independent vars - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( play_.GetOp(j+1) == local::InvOp ); - CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] == j+1 ); - x[j] = taylor_[ ind_taddr_[j] * cap_order_taylor_ + 0]; - } - // zero order coefficients for dependent vars - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - y[i] = taylor_[ dep_taddr_[i] * cap_order_taylor_ + 0]; - } - // maximum zero order coefficient not counting BeginOp at beginning - // (which is correpsonds to uninitialized memory). - for(i = 1; i < num_var_tape_; i++) - { if( abs_geq(taylor_[i*cap_order_taylor_+0] , max_taylor) ) - max_taylor = taylor_[i*cap_order_taylor_+0]; - } - } -# endif - - // create the optimized recording - local::optimize::optimize_run(options, n, dep_taddr_, &play_, &rec); - - // number of variables in the recording - num_var_tape_ = rec.num_var_rec(); - - // now replace the recording - play_.get(rec); - - // set flag so this function knows it has been optimized - has_been_optimized_ = true; - - // free memory allocated for sparse Jacobian calculation - // (the results are no longer valid) - for_jac_sparse_pack_.resize(0, 0); - for_jac_sparse_set_.resize(0,0); - - // free old Taylor coefficient memory - taylor_.free(); - num_order_taylor_ = 0; - cap_order_taylor_ = 0; - - // resize and initilaize conditional skip vector - // (must use player size because it now has the recoreder information) - cskip_op_.erase(); - cskip_op_.extend( play_.num_op_rec() ); - -# ifndef NDEBUG - if( check_zero_order ) - { - // zero order forward calculation using new operation sequence - check = Forward(0, x); - - // check results - Base eps = 10. * CppAD::numeric_limits::epsilon(); - for(i = 0; i < m; i++) CPPAD_ASSERT_KNOWN( - abs_geq( eps * max_taylor , check[i] - y[i] ) , - "Error during check of f.optimize()." - ); - - // Erase memory that this calculation was done so NDEBUG gives - // same final state for this object (from users perspective) - num_order_taylor_ = 0; - } -# endif -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/ordered.hpp b/ct_core/include/ct/external/cppad/core/ordered.hpp deleted file mode 100644 index 377ba60bf..000000000 --- a/ct_core/include/ct/external/cppad/core/ordered.hpp +++ /dev/null @@ -1,102 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_ORDERED_HPP -# define CPPAD_CORE_ORDERED_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -/*! -\file ordered.hpp -Check and AD values ordering properties relative to zero. -*/ - -// GreaterThanZero ============================================================ -/*! -Check if an AD is greater than zero. - -\param x -value we are checking. - -\return -returns true iff the \c x is greater than zero. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool GreaterThanZero(const AD &x) -{ return GreaterThanZero(x.value_); } -// GreaterThanOrZero ========================================================= -/*! -Check if an AD is greater than or equal zero. - -\param x -value we are checking. - -\return -returns true iff the \c x is greater than or equal zero. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool GreaterThanOrZero(const AD &x) -{ return GreaterThanOrZero(x.value_); } -// LessThanZero ============================================================ -/*! -Check if an AD is less than zero. - -\param x -value we are checking. - -\return -returns true iff the \c x is less than zero. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool LessThanZero(const AD &x) -{ return LessThanZero(x.value_); } -// LessThanOrZero ========================================================= -/*! -Check if an AD is less than or equal zero. - -\param x -value we are checking. - -\return -returns true iff the \c x is less than or equal zero. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool LessThanOrZero(const AD &x) -{ return LessThanOrZero(x.value_); } -// abs_geq ========================================================= -/*! -Check if absolute value of one AD is greater or equal another. - -\param x -value we are checking if it is greater than or equal other. - -\param y -value we are checking if it is less than other. - -\return -returns true iff the absolute value of \c x is greater than or equal -absolute value of \c y. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool abs_geq(const AD& x, const AD& y) -{ return abs_geq(x.value_, y.value_); } -// ============================================================================ -} // END_CPPAD_NAMESPACE -# endif - diff --git a/ct_core/include/ct/external/cppad/core/par_var.hpp b/ct_core/include/ct/external/cppad/core/par_var.hpp deleted file mode 100644 index 4e1e0cdb5..000000000 --- a/ct_core/include/ct/external/cppad/core/par_var.hpp +++ /dev/null @@ -1,119 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_PAR_VAR_HPP -# define CPPAD_CORE_PAR_VAR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* ---------------------------------------------------------------------------- - -$begin ParVar$$ -$spell - VecAD - const - bool -$$ - -$section Is an AD Object a Parameter or Variable$$ - -$head Syntax$$ -$icode%b% = Parameter(%x%)%$$ -$pre -$$ -$icode%b% = Variable(%x%)%$$ - - -$head Purpose$$ -Determine if $icode x$$ is a -$cref/parameter/glossary/Parameter/$$ or -$cref/variable/glossary/Variable/$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const AD<%Base%> &%x% - const VecAD<%Base%> &%x% -%$$ - -$head b$$ -The return value $icode b$$ has prototype -$codei% - bool %b% -%$$ -The return value for $code Parameter$$ ($code Variable$$) -is true if and only if $icode x$$ is a parameter (variable). -Note that a $cref/VecAD/VecAD/$$ object -is a variable if any element of the vector depends on the independent -variables. - -$head Operation Sequence$$ -The result of this operation is not an -$cref/AD of Base/glossary/AD of Base/$$ object. -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Example$$ -$children% - example/par_var.cpp -%$$ -The file -$cref par_var.cpp$$ -contains an example and test of these functions. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -namespace CppAD { - // Parameter - template - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION - bool Parameter(const AD &x) - { if( x.tape_id_ == 0 ) - return true; - size_t thread = size_t(x.tape_id_ % CPPAD_MAX_NUM_THREADS); - return x.tape_id_ != *AD::tape_id_ptr(thread); - } - - template - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION - bool Parameter(const VecAD &x) - { if( x.tape_id_ == 0 ) - return true; - size_t thread = size_t(x.tape_id_ % CPPAD_MAX_NUM_THREADS); - return x.tape_id_ != *AD::tape_id_ptr(thread); - } - - // Variable - template - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION - bool Variable(const AD &x) - { if( x.tape_id_ == 0 ) - return false; - size_t thread = size_t(x.tape_id_ % CPPAD_MAX_NUM_THREADS); - return x.tape_id_ == *AD::tape_id_ptr(thread); - } - - template - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION - bool Variable(const VecAD &x) - { if( x.tape_id_ == 0 ) - return false; - size_t thread = size_t(x.tape_id_ % CPPAD_MAX_NUM_THREADS); - return x.tape_id_ == *AD::tape_id_ptr(thread); - } -} -// END CppAD namespace - - -# endif diff --git a/ct_core/include/ct/external/cppad/core/parallel_ad.hpp b/ct_core/include/ct/external/cppad/core/parallel_ad.hpp deleted file mode 100644 index faa430462..000000000 --- a/ct_core/include/ct/external/cppad/core/parallel_ad.hpp +++ /dev/null @@ -1,118 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_PARALLEL_AD_HPP -# define CPPAD_CORE_PARALLEL_AD_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin parallel_ad$$ -$spell - CppAD - num - std -$$ - -$section Enable AD Calculations During Parallel Mode$$ - -$head Syntax$$ -$codei%parallel_ad<%Base%>()%$$ - -$head Purpose$$ -The function -$codei%parallel_ad<%Base%>()%$$ -must be called before any $codei%AD<%Base>%$$ objects are used -in $cref/parallel/ta_in_parallel/$$ mode. -In addition, if this routine is called after one is done using -parallel mode, it will free extra memory used to keep track of -the multiple $codei%AD<%Base%>%$$ tapes required for parallel execution. - -$head Discussion$$ -By default, for each $codei%AD<%Base%>%$$ class there is only one -tape that records $cref/AD of Base/glossary/AD of Base/$$ operations. -This tape is a global variable and hence it cannot be used -by multiple threads at the same time. -The $cref/parallel_setup/ta_parallel_setup/$$ function informs CppAD of the -maximum number of threads that can be active in parallel mode. -This routine does extra setup -(and teardown) for the particular $icode Base$$ type. - -$head CheckSimpleVector$$ -This routine has the side effect of calling the routines -$codei% - CheckSimpleVector< %Type%, CppAD::vector<%Type%> >() -%$$ -where $icode Type$$ is $icode Base$$ and $codei%AD<%Base%>%$$. - -$head Example$$ -The files -$cref team_openmp.cpp$$, -$cref team_bthread.cpp$$, and -$cref team_pthread.cpp$$, -contain examples and tests that implement this function. - -$head Restriction$$ -This routine cannot be called in parallel mode or while -there is a tape recording $codei%AD<%Base%>%$$ operations. - -$end ------------------------------------------------------------------------------ -*/ - -# include - -// BEGIN CppAD namespace -namespace CppAD { - -/*! -Enable parallel execution mode with AD by initializing -static variables that my be used. -*/ - -template -void parallel_ad(void) -{ CPPAD_ASSERT_KNOWN( - ! thread_alloc::in_parallel() , - "parallel_ad must be called before entering parallel execution mode." - ); - CPPAD_ASSERT_KNOWN( - AD::tape_ptr() == CPPAD_NULL , - "parallel_ad cannot be called while a tape recording is in progress" - ); - - // ensure statics in following functions are initialized - elapsed_seconds(); - ErrorHandler::Current(); - local::NumArg(local::BeginOp); - local::NumRes(local::BeginOp); - local::one_element_std_set(); - local::two_element_std_set(); - - // the sparse_pack class has member functions with static data - local::sparse_pack sp; - sp.resize(1, 1); // so can call add_element - sp.add_element(0, 0); // has static data - sp.clear(0); // has static data - sp.is_element(0, 0); // has static data - local::sparse_pack::const_iterator itr(sp, 0); // has static data - ++itr; // has static data - - // statics that depend on the value of Base - AD::tape_id_handle(0); - AD::tape_handle(0); - AD::tape_manage(tape_manage_clear); - discrete::List(); - CheckSimpleVector< Base, CppAD::vector >(); - CheckSimpleVector< AD, CppAD::vector< AD > >(); - -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/pow.hpp b/ct_core/include/ct/external/cppad/core/pow.hpp deleted file mode 100644 index a1873d66b..000000000 --- a/ct_core/include/ct/external/cppad/core/pow.hpp +++ /dev/null @@ -1,258 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_POW_HPP -# define CPPAD_CORE_POW_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin pow$$ -$spell - Vec - std - namespace - CppAD - const -$$ - - -$section The AD Power Function$$ -$mindex pow exponent$$ - -$head Syntax$$ -$icode%z% = pow(%x%, %y%)%$$ - -$head See Also$$ -$cref pow_int$$ - - -$head Purpose$$ -Determines the value of the power function which is defined by -$latex \[ - {\rm pow} (x, y) = x^y -\] $$ -This version of the $code pow$$ function may use -logarithms and exponentiation to compute derivatives. -This will not work if $icode x$$ is less than or equal zero. -If the value of $icode y$$ is an integer, -the $cref pow_int$$ function is used to compute this value -using only multiplication (and division if $icode y$$ is negative). -(This will work even if $icode x$$ is less than or equal zero.) - -$head x$$ -The argument $icode x$$ has one of the following prototypes -$codei% - const %Base%& %x% - const AD<%Base%>& %x% - const VecAD<%Base%>::reference& %x% -%$$ - -$head y$$ -The argument $icode y$$ has one of the following prototypes -$codei% - const %Base%& %y% - const AD<%Base%>& %y% - const VecAD<%Base%>::reference& %y% -%$$ - -$head z$$ -If both $icode x$$ and $icode y$$ are $icode Base$$ objects, -the result $icode z$$ is also a $icode Base$$ object. -Otherwise, it has prototype -$codei% - AD<%Base%> %z% -%$$ - -$head Operation Sequence$$ -This is an AD of $icode Base$$ -$cref/atomic operation/glossary/Operation/Atomic/$$ -and hence is part of the current -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Example$$ -$children% - example/pow.cpp -%$$ -The file -$cref pow.cpp$$ -is an examples and tests of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -// case where x and y are AD ----------------------------------------- -template AD -pow(const AD& x, const AD& y) -{ - // compute the Base part - AD result; - result.value_ = pow(x.value_, y.value_); - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - // check if there is a recording in progress - local::ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return result; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_x = x.tape_id_ == tape_id; - bool var_y = y.tape_id_ == tape_id; - - if( var_x ) - { if( var_y ) - { // result = variable^variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::PowvvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::PowvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(x.taddr_, y.taddr_); - - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::PowvvOp); - - // make result a variable - result.tape_id_ = tape_id; - } - else if( IdenticalZero( y.value_ ) ) - { // result = variable^0 - } - else - { // result = variable^parameter - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::PowvpOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::PowvpOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(y.value_); - tape->Rec_.PutArg(x.taddr_, p); - - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::PowvpOp); - - // make result a variable - result.tape_id_ = tape_id; - } - } - else if( var_y ) - { if( IdenticalZero(x.value_) ) - { // result = 0^variable - } - else - { // result = parameter^variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::PowpvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::PowpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(x.value_); - tape->Rec_.PutArg(p, y.taddr_); - - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::PowpvOp); - - // make result a variable - result.tape_id_ = tape_id; - } - } - return result; -} -// ========================================================================= -// Fold operations in same way as CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR(Op) -// ------------------------------------------------------------------------- -// Operations with VecAD_reference and AD only - -template AD -pow(const AD& x, const VecAD_reference& y) -{ return pow(x, y.ADBase()); } - -template AD -pow(const VecAD_reference& x, const VecAD_reference& y) -{ return pow(x.ADBase(), y.ADBase()); } - -template AD -pow(const VecAD_reference& x, const AD& y) -{ return pow(x.ADBase(), y); } -// ------------------------------------------------------------------------- -// Operations with Base - -template AD -pow(const Base& x, const AD& y) -{ return pow(AD(x), y); } - -template AD -pow(const Base& x, const VecAD_reference& y) -{ return pow(AD(x), y.ADBase()); } - -template AD -pow(const AD& x, const Base& y) -{ return pow(x, AD(y)); } - -template AD -pow(const VecAD_reference& x, const Base& y) -{ return pow(x.ADBase(), AD(y)); } -// ------------------------------------------------------------------------- -// Operations with double - -template AD -pow(const double& x, const AD& y) -{ return pow(AD(x), y); } - -template AD -pow(const double& x, const VecAD_reference& y) -{ return pow(AD(x), y.ADBase()); } - -template AD -pow(const AD& x, const double& y) -{ return pow(x, AD(y)); } - -template AD -pow(const VecAD_reference& x, const double& y) -{ return pow(x.ADBase(), AD(y)); } -// ------------------------------------------------------------------------- -// Special case to avoid ambuigity when Base is double - -inline AD -pow(const double& x, const AD& y) -{ return pow(AD(x), y); } - -inline AD -pow(const double& x, const VecAD_reference& y) -{ return pow(AD(x), y.ADBase()); } - -inline AD -pow(const AD& x, const double& y) -{ return pow(x, AD(y)); } - -inline AD -pow(const VecAD_reference& x, const double& y) -{ return pow(x.ADBase(), AD(y)); } - -// ========================================================================= -// Fold operations for the cases where x is an int, -// but let cppad/pow_int.hpp handle the cases where y is an int. -// ------------------------------------------------------------------------- -template AD pow -(const int& x, const VecAD_reference& y) -{ return pow(AD(x), y.ADBase()); } - -template AD pow -(const int& x, const AD& y) -{ return pow(AD(x), y); } - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/print_for.hpp b/ct_core/include/ct/external/cppad/core/print_for.hpp deleted file mode 100644 index ddc234e62..000000000 --- a/ct_core/include/ct/external/cppad/core/print_for.hpp +++ /dev/null @@ -1,220 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_PRINT_FOR_HPP -# define CPPAD_CORE_PRINT_FOR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin PrintFor$$ -$spell - pos - var - VecAD - std - cout - const -$$ - - -$section Printing AD Values During Forward Mode$$ -$mindex print text output debug$$ - -$head Syntax$$ -$icode%f%.Forward(0, %x%) -%$$ -$codei%PrintFor(%before%, %var%) -%$$ -$codei%PrintFor(%pos%, %before%, %var%, %after%) -%$$ - -$head Purpose$$ -The $cref/zero order forward/forward_zero/$$ mode command -$codei% - %f%.Forward(0, %x%) -%$$ -assigns the -$cref/independent variable/glossary/Tape/Independent Variable/$$ vector -equal to $icode x$$. -It then computes a value for all of the dependent variables in the -$cref/operation sequence/glossary/Operation/Sequence/$$ corresponding -to $icode f$$. -Putting a $code PrintFor$$ in the operation sequence will -cause the value of $icode var$$, corresponding to $icode x$$, -to be printed during zero order forward operations. - -$head f.Forward(0, x)$$ -The objects $icode f$$, $icode x$$, and the purpose -for this operation, are documented in $cref Forward$$. - -$head pos$$ -If present, the argument $icode pos$$ has one of the following prototypes -$codei% - const AD<%Base%>& %pos% - const VecAD<%Base%>::reference& %pos% -%$$ -In this case -the text and $icode var$$ will be printed if and only if -$icode pos$$ is not greater than zero and a finite number. - -$head before$$ -The argument $icode before$$ has prototype -$codei% - const char* %before% -%$$ -This text is written to $code std::cout$$ before $icode var$$. - -$head var$$ -The argument $icode var$$ has one of the following prototypes -$codei% - const AD<%Base%>& %var% - const VecAD<%Base%>::reference& %var% -%$$ -The value of $icode var$$, that corresponds to $icode x$$, -is written to $code std::cout$$ during the execution of -$codei% - %f%.Forward(0, %x%) -%$$ -Note that $icode var$$ may be a -$cref/variable/glossary/Variable/$$ or -$cref/parameter/glossary/Parameter/$$. -(A parameters value does not depend on the value of -the independent variable vector $icode x$$.) - -$head after$$ -The argument $icode after$$ has prototype -$codei% - const char* %after% -%$$ -This text is written to $code std::cout$$ after $icode var$$. - -$head Redirecting Output$$ -You can redirect this output to any standard output stream; see the -$cref/s/forward_order/s/$$ in the forward mode documentation. - -$head Discussion$$ -This is helpful for understanding why tape evaluations -have trouble. -For example, if one of the operations in $icode f$$ is -$codei%log(%var%)%$$ and $icode%var% <= 0%$$, -the corresponding result will be $cref nan$$. - -$head Alternative$$ -The $cref ad_output$$ section describes the normal -printing of values; i.e., printing when the corresponding -code is executed. - -$head Example$$ -$children% - print_for/print_for.cpp% - example/print_for.cpp -%$$ -The program -$cref print_for_cout.cpp$$ -is an example and test that prints to standard output. -The output of this program -states the conditions for passing and failing the test. -The function -$cref print_for_string.cpp$$ -is an example and test that prints to an standard string stream. -This function automatically check for correct output. - -$end ------------------------------------------------------------------------------- -*/ - -# include - -namespace CppAD { - template - void PrintFor(const AD& pos, - const char *before, const AD& var, const char* after) - { CPPAD_ASSERT_NARG_NRES(local::PriOp, 5, 0); - - // check for case where we are not recording operations - local::ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return; - - CPPAD_ASSERT_KNOWN( - std::strlen(before) <= 1000 , - "PrintFor: length of before is greater than 1000 characters" - ); - CPPAD_ASSERT_KNOWN( - std::strlen(after) <= 1000 , - "PrintFor: length of after is greater than 1000 characters" - ); - size_t ind0, ind1, ind2, ind3, ind4; - - // ind[0] = base 2 representation of the value [Var(pos), Var(var)] - ind0 = 0; - - // ind[1] = address for pos - if( Parameter(pos) ) - ind1 = tape->Rec_.PutPar(pos.value_); - else - { ind0 += 1; - ind1 = pos.taddr_; - } - - // ind[2] = address of before - ind2 = tape->Rec_.PutTxt(before); - - // ind[3] = address for var - if( Parameter(var) ) - ind3 = tape->Rec_.PutPar(var.value_); - else - { ind0 += 2; - ind3 = var.taddr_; - } - - // ind[4] = address of after - ind4 = tape->Rec_.PutTxt(after); - - // put the operator in the tape - tape->Rec_.PutArg(ind0, ind1, ind2, ind3, ind4); - tape->Rec_.PutOp(local::PriOp); - } - // Fold all other cases into the case above - template - void PrintFor(const char* before, const AD& var) - { PrintFor(AD(0), before, var, "" ); } - // - template - void PrintFor(const char* before, const VecAD_reference& var) - { PrintFor(AD(0), before, var.ADBase(), "" ); } - // - template - void PrintFor( - const VecAD_reference& pos , - const char *before , - const VecAD_reference& var , - const char *after ) - { PrintFor(pos.ADBase(), before, var.ADBase(), after); } - // - template - void PrintFor( - const VecAD_reference& pos , - const char *before , - const AD& var , - const char *after ) - { PrintFor(pos.ADBase(), before, var, after); } - // - template - void PrintFor( - const AD& pos , - const char *before , - const VecAD_reference& var , - const char *after ) - { PrintFor(pos, before, var.ADBase(), after); } -} - -# endif diff --git a/ct_core/include/ct/external/cppad/core/rev_one.hpp b/ct_core/include/ct/external/cppad/core/rev_one.hpp deleted file mode 100644 index 340868780..000000000 --- a/ct_core/include/ct/external/cppad/core/rev_one.hpp +++ /dev/null @@ -1,163 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_REV_ONE_HPP -# define CPPAD_CORE_REV_ONE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin RevOne$$ -$spell - dw - Taylor - const -$$ - - - - -$section First Order Derivative: Driver Routine$$ -$mindex derivative easy$$ - -$head Syntax$$ -$icode%dw% = %f%.RevOne(%x%, %i%)%$$ - - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -The syntax above sets $icode dw$$ to the -derivative of $latex F_i$$ with respect to $latex x$$; i.e., -$latex \[ -dw = -F_i^{(1)} (x) -= \left[ - \D{ F_i }{ x_0 } (x) , \cdots , \D{ F_i }{ x_{n-1} } (x) -\right] -\] $$ - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/RevOne Uses Forward/RevOne/RevOne Uses Forward/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -(see $cref/Vector/RevOne/Vector/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the derivative. - -$head i$$ -The index $icode i$$ has prototype -$codei% - size_t %i% -%$$ -and is less than $latex m$$, the dimension of the -$cref/range/seq_property/Range/$$ space for $icode f$$. -It specifies the -component of $latex F$$ that we are computing the derivative of. - -$head dw$$ -The result $icode dw$$ has prototype -$codei% - %Vector% %dw% -%$$ -(see $cref/Vector/RevOne/Vector/$$ below) -and its size is $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -The value of $icode dw$$ is the derivative of $latex F_i$$ -evaluated at $icode x$$; i.e., -for $latex j = 0 , \ldots , n - 1 $$ -$latex \[. - dw[ j ] = \D{ F_i }{ x_j } ( x ) -\] $$ - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Base$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head RevOne Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to $code RevOne$$, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0, %x%)%$$ -and the other coefficients are unspecified. - -$head Example$$ -$children% - example/rev_one.cpp -%$$ -The routine -$cref/RevOne/rev_one.cpp/$$ is both an example and test. -It returns $code true$$, if it succeeds and $code false$$ otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -template -Vector ADFun::RevOne(const Vector &x, size_t i) -{ size_t i1; - - size_t n = Domain(); - size_t m = Range(); - - // check Vector is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( - x.size() == n, - "RevOne: Length of x not equal domain dimension for f" - ); - CPPAD_ASSERT_KNOWN( - i < m, - "RevOne: the index i is not less than range dimension for f" - ); - - // point at which we are evaluating the derivative - Forward(0, x); - - // component which are are taking the derivative of - Vector w(m); - for(i1 = 0; i1 < m; i1++) - w[i1] = 0.; - w[i] = Base(1); - - // dimension the return value - Vector dw(n); - - // compute the return value - dw = Reverse(1, w); - - return dw; -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/rev_sparse_hes.hpp b/ct_core/include/ct/external/cppad/core/rev_sparse_hes.hpp deleted file mode 100644 index 2ff10bda8..000000000 --- a/ct_core/include/ct/external/cppad/core/rev_sparse_hes.hpp +++ /dev/null @@ -1,622 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_REV_SPARSE_HES_HPP -# define CPPAD_CORE_REV_SPARSE_HES_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin RevSparseHes$$ -$spell - std - VecAD - Jacobian - Jac - Hessian - Hes - const - Bool - Dep - proportional - var - cpp -$$ - -$section Hessian Sparsity Pattern: Reverse Mode$$ - -$head Syntax$$ -$icode%h% = %f%.RevSparseHes(%q%, %s%) -%$$ -$icode%h% = %f%.RevSparseHes(%q%, %s%, %transpose%)%$$ - -$head Purpose$$ -We use $latex F : \B{R}^n \rightarrow \B{R}^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -For a fixed matrix $latex R \in \B{R}^{n \times q}$$ -and a fixed vector $latex S \in \B{R}^{1 \times m}$$, -we define -$latex \[ -\begin{array}{rcl} -H(x) -& = & \partial_x \left[ \partial_u S * F[ x + R * u ] \right]_{u=0} -\\ -& = & R^\R{T} * (S * F)^{(2)} ( x ) -\\ -H(x)^\R{T} -& = & (S * F)^{(2)} ( x ) * R -\end{array} -\] $$ -Given a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex R$$ and the vector $latex S$$, -$code RevSparseHes$$ returns a sparsity pattern for the $latex H(x)$$. - -$head f$$ -The object $icode f$$ has prototype -$codei% - const ADFun<%Base%> %f% -%$$ - -$head x$$ -If the operation sequence in $icode f$$ is -$cref/independent/glossary/Operation/Independent/$$ of -the independent variables in $latex x \in B^n$$, -the sparsity pattern is valid for all values of -(even if it has $cref CondExp$$ or $cref VecAD$$ operations). - -$head q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of columns in $latex R \in \B{R}^{n \times q}$$ -and the number of rows in $latex H(x) \in \B{R}^{q \times n}$$. -It must be the same value as in the previous $cref ForSparseJac$$ call -$codei% - %f%.ForSparseJac(%q%, %r%, %r_transpose%) -%$$ -Note that if $icode r_transpose$$ is true, $icode r$$ in the call above -corresponding to $latex R^\R{T} \in \B{R}^{q \times n}$$ - -$head transpose$$ -The argument $icode transpose$$ has prototype -$codei% - bool %transpose% -%$$ -The default value $code false$$ is used when $icode transpose$$ is not present. - - -$head r$$ -The matrix $latex R$$ is specified by the previous call -$codei% - %f%.ForSparseJac(%q%, %r%, %transpose%) -%$$ -see $cref/r/ForSparseJac/r/$$. -The type of the elements of -$cref/VectorSet/RevSparseHes/VectorSet/$$ must be the -same as the type of the elements of $icode r$$. - -$head s$$ -The argument $icode s$$ has prototype -$codei% - const %VectorSet%& %s% -%$$ -(see $cref/VectorSet/RevSparseHes/VectorSet/$$ below) -If it has elements of type $code bool$$, -its size is $latex m$$. -If it has elements of type $code std::set$$, -its size is one and all the elements of $icode%s%[0]%$$ -are between zero and $latex m - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the vector $icode S$$. - -$head h$$ -The result $icode h$$ has prototype -$codei% - %VectorSet%& %h% -%$$ -(see $cref/VectorSet/RevSparseHes/VectorSet/$$ below). - -$subhead transpose false$$ -If $icode h$$ has elements of type $code bool$$, -its size is $latex q * n$$. -If it has elements of type $code std::set$$, -its size is $latex q$$ and all the set elements are between -zero and $icode%n%-1%$$ inclusive. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex H(x)$$. - -$subhead transpose true$$ -If $icode h$$ has elements of type $code bool$$, -its size is $latex n * q$$. -If it has elements of type $code std::set$$, -its size is $latex n$$ and all the set elements are between -zero and $icode%q%-1%$$ inclusive. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex H(x)^\R{T}$$. - -$head VectorSet$$ -The type $icode VectorSet$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code bool$$ or $code std::set$$; -see $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for a discussion -of the difference. -The type of the elements of -$cref/VectorSet/RevSparseHes/VectorSet/$$ must be the -same as the type of the elements of $icode r$$. - -$head Entire Sparsity Pattern$$ -Suppose that $latex q = n$$ and -$latex R \in \B{R}^{n \times n}$$ is the $latex n \times n$$ identity matrix. -Further suppose that the $latex S$$ is the $th k$$ -$cref/elementary vector/glossary/Elementary Vector/$$; i.e. -$latex \[ -S_j = \left\{ \begin{array}{ll} - 1 & {\rm if} \; j = k - \\ - 0 & {\rm otherwise} -\end{array} \right. -\] $$ -In this case, -the corresponding value $icode h$$ is a -sparsity pattern for the Hessian matrix -$latex F_k^{(2)} (x) \in \B{R}^{n \times n}$$. - -$head Example$$ -$children% - example/rev_sparse_hes.cpp - %example/sparsity_sub.cpp -%$$ -The file -$cref rev_sparse_hes.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. -The file -$cref/sparsity_sub.cpp/sparsity_sub.cpp/RevSparseHes/$$ -contains an example and test of using $code RevSparseHes$$ -to compute the sparsity pattern for a subset of the Hessian. - -$end ------------------------------------------------------------------------------ -*/ -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file rev_sparse_hes.hpp -Reverse mode Hessian sparsity patterns. -*/ -// =========================================================================== -// RevSparseHesCase -/*! -Private helper function for RevSparseHes(q, s) bool sparsity. - -All of the description in the public member function RevSparseHes(q, s) -applies. - -\param set_type -is a \c bool value. This argument is used to dispatch to the proper source -code depending on the vlaue of \c VectorSet::value_type. - -\param transpose -See \c RevSparseHes(q, s). - -\param q -See \c RevSparseHes(q, s). - -\param s -See \c RevSparseHes(q, s). - -\param h -is the return value for the corresponging call to \c RevSparseJac(q, s). -*/ -template -template -void ADFun::RevSparseHesCase( - bool set_type , - bool transpose , - size_t q , - const VectorSet& s , - VectorSet& h ) -{ size_t n = Domain(); - size_t m = Range(); - // - h.resize(q * n ); - - CPPAD_ASSERT_KNOWN( - for_jac_sparse_pack_.n_set() > 0, - "RevSparseHes: previous stored call to ForSparseJac did not " - "use bool for the elements of r." - ); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_set_.n_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_pack_.n_set() == num_var_tape_ ); - // - // temporary indices - size_t i, j; - - // check Vector is Simple VectorSet class with bool elements - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( - q == for_jac_sparse_pack_.end(), - "RevSparseHes: q is not equal to its value\n" - "in the previous call to ForSparseJac with this ADFun object." - ); - CPPAD_ASSERT_KNOWN( - size_t(s.size()) == m, - "RevSparseHes: size of s is not equal to\n" - "range dimension for ADFun object." - ); - - // Array that will hold reverse Jacobian dependency flag. - // Initialize as true for the dependent variables. - local::pod_vector RevJac; - RevJac.extend(num_var_tape_); - for(i = 0; i < num_var_tape_; i++) - RevJac[i] = false; - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - RevJac[ dep_taddr_[i] ] = s[i]; - } - - // vector of sets that will hold reverse Hessain values - local::sparse_pack rev_hes_sparsity; - rev_hes_sparsity.resize(num_var_tape_, q); - - // compute the Hessian sparsity patterns - local::RevHesSweep( - n, - num_var_tape_, - &play_, - for_jac_sparse_pack_, - RevJac.data(), - rev_hes_sparsity - ); - - // return values corresponding to independent variables - CPPAD_ASSERT_UNKNOWN( size_t(h.size()) == n * q ); - for(j = 0; j < n; j++) - { for(i = 0; i < q; i++) - { if( transpose ) - h[ j * q + i ] = false; - else h[ i * n + j ] = false; - } - } - - // j is index corresponding to reverse mode partial - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] < num_var_tape_ ); - - // ind_taddr_[j] is operator taddr for j-th independent variable - CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] == j + 1 ); - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == local::InvOp ); - - // extract the result from rev_hes_sparsity - CPPAD_ASSERT_UNKNOWN( rev_hes_sparsity.end() == q ); - local::sparse_pack::const_iterator itr(rev_hes_sparsity, j + 1); - i = *itr; - while( i < q ) - { if( transpose ) - h[ j * q + i ] = true; - else h[ i * n + j ] = true; - i = *(++itr); - } - } -} -/*! -Private helper function for RevSparseHes(q, s) set sparsity. - -All of the description in the public member function RevSparseHes(q, s) -applies. - -\param set_type -is a \c std::set value. -This argument is used to dispatch to the proper source -code depending on the vlaue of \c VectorSet::value_type. - -\param transpose -See \c RevSparseHes(q, s). - -\param q -See \c RevSparseHes(q, s). - -\param s -See \c RevSparseHes(q, s). - -\param h -is the return value for the corresponging call to \c RevSparseJac(q, s). -*/ -template -template -void ADFun::RevSparseHesCase( - const std::set& set_type , - bool transpose , - size_t q , - const VectorSet& s , - VectorSet& h ) -{ size_t n = Domain(); -# ifndef NDEBUG - size_t m = Range(); -# endif - // - if( transpose ) - h.resize(n); - else h.resize(q); - - CPPAD_ASSERT_KNOWN( - for_jac_sparse_set_.n_set() > 0, - "RevSparseHes: previous stored call to ForSparseJac did not " - "use std::set for the elements of r." - ); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_pack_.n_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_set_.n_set() == num_var_tape_ ); - // - // temporary indices - size_t i, j; - std::set::const_iterator itr_1; - - // check VectorSet is Simple Vector class with sets for elements - CheckSimpleVector, VectorSet>( - local::one_element_std_set(), local::two_element_std_set() - ); - - CPPAD_ASSERT_KNOWN( - q == for_jac_sparse_set_.end(), - "RevSparseHes: q is not equal to its value\n" - "in the previous call to ForSparseJac with this ADFun object." - ); - CPPAD_ASSERT_KNOWN( - s.size() == 1, - "RevSparseHes: size of s is not equal to one." - ); - - // Array that will hold reverse Jacobian dependency flag. - // Initialize as true for the dependent variables. - local::pod_vector RevJac; - RevJac.extend(num_var_tape_); - for(i = 0; i < num_var_tape_; i++) - RevJac[i] = false; - itr_1 = s[0].begin(); - while( itr_1 != s[0].end() ) - { i = *itr_1++; - CPPAD_ASSERT_KNOWN( - i < m, - "RevSparseHes: an element of the set s[0] has value " - "greater than or equal m" - ); - CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - RevJac[ dep_taddr_[i] ] = true; - } - - - // vector of sets that will hold reverse Hessain values - local::sparse_list rev_hes_sparsity; - rev_hes_sparsity.resize(num_var_tape_, q); - - // compute the Hessian sparsity patterns - local::RevHesSweep( - n, - num_var_tape_, - &play_, - for_jac_sparse_set_, - RevJac.data(), - rev_hes_sparsity - ); - - // return values corresponding to independent variables - // j is index corresponding to reverse mode partial - CPPAD_ASSERT_UNKNOWN( size_t(h.size()) == q || transpose ); - CPPAD_ASSERT_UNKNOWN( size_t(h.size()) == n || ! transpose ); - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] < num_var_tape_ ); - CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] == j + 1 ); - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == local::InvOp ); - - // extract the result from rev_hes_sparsity - // and add corresponding elements to result sets in h - CPPAD_ASSERT_UNKNOWN( rev_hes_sparsity.end() == q ); - local::sparse_list::const_iterator itr_2(rev_hes_sparsity, j+1); - i = *itr_2; - while( i < q ) - { if( transpose ) - h[j].insert(i); - else h[i].insert(j); - i = *(++itr_2); - } - } -} - -// =========================================================================== -// RevSparseHes - -/*! -User API for Hessian sparsity patterns using reverse mode. - -The C++ source code corresponding to this operation is -\verbatim - h = f.RevSparseHes(q, r) -\endverbatim - -\tparam Base -is the base type for this recording. - -\tparam VectorSet -is a simple vector with elements of type \c bool -or \c std::set. - -\param transpose -is true (false) if \c is is equal to \f$ H(x) \f$ (\f$ H(x)^T \f$) -where -\f[ - H(x) = R^T (S * F)^{(2)} (x) -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \a x is any argument value. - -\param q -is the value of \a q in the -by the previous call of the form -\verbatim - f.ForSparseJac(q, r, packed) -\endverbatim -The value \c r in this call is a sparsity pattern for the matrix \f$ R \f$. -The type of the element of \c r for the previous call to \c ForSparseJac -must be the same as the type of the elements of \c s. - -\param s -is a vector with size \c m that specifies the sparsity pattern -for the vector \f$ S \f$, -where \c m is the number of dependent variables -corresponding to the operation sequence stored in \a play. - -\return -If \c transpose is false (true), -the return vector is a sparsity pattern for \f$ H(x) \f$ (\f$ H(x)^T \f$). -\f[ - H(x) = R^T ( S * F)^{(2)} (x) -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \a x is any argument value. -*/ - -template -template -VectorSet ADFun::RevSparseHes( - size_t q, const VectorSet& s, bool transpose -) -{ VectorSet h; - typedef typename VectorSet::value_type Set_type; - - // Should check to make sure q is same as in previous call to - // forward sparse Jacobian. - RevSparseHesCase( - Set_type() , - transpose , - q , - s , - h - ); - - return h; -} -// =========================================================================== -// RevSparseHesCheckpoint -/*! -Hessian sparsity patterns calculation used by checkpoint functions. - -\tparam Base -is the base type for this recording. - -\param transpose -is true (false) h is equal to \f$ H(x) \f$ (\f$ H(x)^T \f$) -where -\f[ - H(x) = R^T (S * F)^{(2)} (x) -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \f$ x \f$ is any argument value. - -\param q -is the value of q in the by the previous call of the form -\verbatim - f.ForSparseJac(q, r) -\endverbatim -The value r in this call is a sparsity pattern for the matrix \f$ R \f$. - -\param s -is a vector with size m that specifies the sparsity pattern -for the vector \f$ S \f$, -where m is the number of dependent variables -corresponding to the operation sequence stored in play_. - -\param h -The input size and elements of h do not matter. -On output, h is the sparsity pattern for the matrix \f$ H(x) \f$ -or \f$ H(x)^T \f$ depending on transpose. - -\par Assumptions -The forward jacobian sparsity pattern must be currently stored -in this ADFUN object. -*/ -template -void ADFun::RevSparseHesCheckpoint( - size_t q , - vector& s , - bool transpose , - local::sparse_list& h ) -{ size_t n = Domain(); - size_t m = Range(); - - // checkpoint functions should get this right - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_pack_.n_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_set_.n_set() == num_var_tape_ ); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_set_.end() == q ); - CPPAD_ASSERT_UNKNOWN( s.size() == m ); - - // Array that holds the reverse Jacobiain dependcy flags. - // Initialize as true for dependent variables, flase for others. - local::pod_vector RevJac; - RevJac.extend(num_var_tape_); - for(size_t i = 0; i < num_var_tape_; i++) - RevJac[i] = false; - for(size_t i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ) - RevJac[ dep_taddr_[i] ] = s[i]; - } - - // holds reverse Hessian sparsity pattern for all variables - local::sparse_list rev_hes_sparsity; - rev_hes_sparsity.resize(num_var_tape_, q); - - // compute Hessian sparsity pattern for all variables - local::RevHesSweep( - n, - num_var_tape_, - &play_, - for_jac_sparse_set_, - RevJac.data(), - rev_hes_sparsity - ); - - // dimension the return value - if( transpose ) - h.resize(n, q); - else - h.resize(q, n); - - // j is index corresponding to reverse mode partial - for(size_t j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] < num_var_tape_ ); - - // ind_taddr_[j] is operator taddr for j-th independent variable - CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] == j + 1 ); - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == local::InvOp ); - - // extract the result from rev_hes_sparsity - CPPAD_ASSERT_UNKNOWN( rev_hes_sparsity.end() == q ); - local::sparse_list::const_iterator itr(rev_hes_sparsity, j + 1); - size_t i = *itr; - while( i < q ) - { if( transpose ) - h.add_element(j, i); - else h.add_element(i, j); - i = *(++itr); - } - } -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/rev_sparse_jac.hpp b/ct_core/include/ct/external/cppad/core/rev_sparse_jac.hpp deleted file mode 100644 index 82148a2e6..000000000 --- a/ct_core/include/ct/external/cppad/core/rev_sparse_jac.hpp +++ /dev/null @@ -1,627 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_REV_SPARSE_JAC_HPP -# define CPPAD_CORE_REV_SPARSE_JAC_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin RevSparseJac$$ -$spell - optimizer - nz - CondExpRel - std - VecAD - var - Jacobian - Jac - const - Bool - Dep - proportional -$$ - -$section Jacobian Sparsity Pattern: Reverse Mode$$ -$mindex RevSparseJac sparse$$ - -$head Syntax$$ -$icode%s% = %f%.RevSparseJac(%q%, %r%) -%$$ -$icode%s% = %f%.RevSparseJac(%q%, %r%, %transpose%, %dependency%)%$$ - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -For a fixed matrix $latex R \in B^{q \times m}$$, -the Jacobian of $latex R * F( x )$$ -with respect to $latex x$$ is -$latex \[ - S(x) = R * F^{(1)} ( x ) -\] $$ -Given a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for $latex R$$, -$code RevSparseJac$$ returns a sparsity pattern for the $latex S(x)$$. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ - -$head x$$ -If the operation sequence in $icode f$$ is -$cref/independent/glossary/Operation/Independent/$$ of -the independent variables in $latex x \in B^n$$, -the sparsity pattern is valid for all values of -(even if it has $cref CondExp$$ or $cref VecAD$$ operations). - -$head q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of rows in -$latex R \in B^{q \times m}$$ and the -Jacobian $latex S(x) \in B^{q \times n}$$. - -$head transpose$$ -The argument $icode transpose$$ has prototype -$codei% - bool %transpose% -%$$ -The default value $code false$$ is used when $icode transpose$$ is not present. - -$head dependency$$ -The argument $icode dependency$$ has prototype -$codei% - bool %dependency% -%$$ -If $icode dependency$$ is true, -the $cref/dependency pattern/dependency.cpp/Dependency Pattern/$$ -(instead of sparsity pattern) is computed. - -$head r$$ -The argument $icode s$$ has prototype -$codei% - const %VectorSet%& %r% -%$$ -see $cref/VectorSet/RevSparseJac/VectorSet/$$ below. - -$subhead transpose false$$ -If $icode r$$ has elements of type $code bool$$, -its size is $latex q * m$$. -If it has elements of type $code std::set$$, -its size is $icode q$$ and all its set elements are between -zero and $latex m - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex R \in B^{q \times m}$$. - -$subhead transpose true$$ -If $icode r$$ has elements of type $code bool$$, -its size is $latex m * q$$. -If it has elements of type $code std::set$$, -its size is $icode m$$ and all its set elements are between -zero and $latex q - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex R^\R{T} \in B^{m \times q}$$. - -$head s$$ -The return value $icode s$$ has prototype -$codei% - %VectorSet% %s% -%$$ -see $cref/VectorSet/RevSparseJac/VectorSet/$$ below. - -$subhead transpose false$$ -If it has elements of type $code bool$$, -its size is $latex q * n$$. -If it has elements of type $code std::set$$, -its size is $icode q$$ and all its set elements are between -zero and $latex n - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex S(x) \in {q \times n}$$. - -$subhead transpose true$$ -If it has elements of type $code bool$$, -its size is $latex n * q$$. -If it has elements of type $code std::set$$, -its size is $icode n$$ and all its set elements are between -zero and $latex q - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex S(x)^\R{T} \in {n \times q}$$. - -$head VectorSet$$ -The type $icode VectorSet$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code bool$$ or $code std::set$$; -see $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for a discussion -of the difference. - -$head Entire Sparsity Pattern$$ -Suppose that $latex q = m$$ and -$latex R$$ is the $latex m \times m$$ identity matrix. -In this case, -the corresponding value for $icode s$$ is a -sparsity pattern for the Jacobian $latex S(x) = F^{(1)} ( x )$$. - -$head Example$$ -$children% - example/rev_sparse_jac.cpp -%$$ -The file -$cref rev_sparse_jac.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file rev_sparse_jac.hpp -Reverse mode Jacobian sparsity patterns. -*/ -// ========================================================================= -// RevSparseJacCase - -/*! -Private helper function for RevSparseJac(q, r, transpose) boolean sparsity. - -All of the description in the public member function -\c RevSparseJac(q, r, transpose) apply. - -\param set_type -is a \c bool value. -This argument is used to dispatch to the proper source code -depending on the value of \c VectorSet::value_type. - -\param transpose -See \c RevSparseJac(q, r, transpose, dependency) - -\param dependency -See \c RevSparseJac(q, r, transpose, dependency) - -\param q -See \c RevSparseJac(q, r, transpose, dependency) - -\param r -See \c RevSparseJac(q, r, transpose, dependency) - -\param s -is the return value for the corresponding call to -RevSparseJac(q, r, transpose). -*/ - -template -template -void ADFun::RevSparseJacCase( - bool set_type , - bool transpose , - bool dependency , - size_t q , - const VectorSet& r , - VectorSet& s ) -{ size_t n = Domain(); - size_t m = Range(); - - // dimension of the result vector - s.resize( q * n ); - - // temporary indices - size_t i, j; - - // check VectorSet is Simple Vector class with bool elements - CheckSimpleVector(); - // - CPPAD_ASSERT_KNOWN( - q > 0, - "RevSparseJac: q is not greater than zero" - ); - CPPAD_ASSERT_KNOWN( - size_t(r.size()) == q * m, - "RevSparseJac: size of r is not equal to\n" - "q times range dimension for ADFun object." - ); - // - // vector of sets that will hold the results - local::sparse_pack var_sparsity; - var_sparsity.resize(num_var_tape_, q); - - // The sparsity pattern corresponding to the dependent variables - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - if( transpose ) - { for(j = 0; j < q; j++) if( r[ i * q + j ] ) - var_sparsity.add_element( dep_taddr_[i], j ); - } - else - { for(j = 0; j < q; j++) if( r[ j * m + i ] ) - var_sparsity.add_element( dep_taddr_[i], j ); - } - } - - // evaluate the sparsity patterns - local::RevJacSweep( - dependency, - n, - num_var_tape_, - &play_, - var_sparsity - ); - - // return values corresponding to dependent variables - CPPAD_ASSERT_UNKNOWN( size_t(s.size()) == q * n ); - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] == (j+1) ); - - // ind_taddr_[j] is operator taddr for j-th independent variable - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == local::InvOp ); - - // extract the result from var_sparsity - if( transpose ) - { for(i = 0; i < q; i++) - s[ j * q + i ] = false; - } - else - { for(i = 0; i < q; i++) - s[ i * n + j ] = false; - } - CPPAD_ASSERT_UNKNOWN( var_sparsity.end() == q ); - local::sparse_pack::const_iterator itr(var_sparsity, j+1); - i = *itr; - while( i < q ) - { if( transpose ) - s[ j * q + i ] = true; - else s[ i * n + j ] = true; - i = *(++itr); - } - } -} - -/*! -Private helper function for RevSparseJac(q, r, transpose) set sparsity - -All of the description in the public member function -\c RevSparseJac(q, r, transpose) apply. - -\param set_type -is a \c std::set object. -This argument is used to dispatch to the proper source code -depending on the value of \c VectorSet::value_type. - -\param transpose -See \c RevSparseJac(q, r, transpose, dependency) - -\param dependency -See \c RevSparseJac(q, r, transpose, dependency) - -\param q -See \c RevSparseJac(q, r, transpose, dependency) - -\param r -See \c RevSparseJac(q, r, transpose, dependency) - -\param s -is the return value for the corresponding call to RevSparseJac(q, r, transpose) -*/ - -template -template -void ADFun::RevSparseJacCase( - const std::set& set_type , - bool transpose , - bool dependency , - size_t q , - const VectorSet& r , - VectorSet& s ) -{ // dimension of the result vector - if( transpose ) - s.resize( Domain() ); - else s.resize( q ); - - // temporary indices - size_t i, j; - std::set::const_iterator itr_1; - - // check VectorSet is Simple Vector class with sets for elements - CheckSimpleVector, VectorSet>( - local::one_element_std_set(), local::two_element_std_set() - ); - - // domain dimensions for F - size_t n = ind_taddr_.size(); - size_t m = dep_taddr_.size(); - - CPPAD_ASSERT_KNOWN( - q > 0, - "RevSparseJac: q is not greater than zero" - ); - CPPAD_ASSERT_KNOWN( - size_t(r.size()) == q || transpose, - "RevSparseJac: size of r is not equal to q and transpose is false." - ); - CPPAD_ASSERT_KNOWN( - size_t(r.size()) == m || ! transpose, - "RevSparseJac: size of r is not equal to m and transpose is true." - ); - - // vector of lists that will hold the results - local::sparse_list var_sparsity; - var_sparsity.resize(num_var_tape_, q); - - // The sparsity pattern corresponding to the dependent variables - if( transpose ) - { for(i = 0; i < m; i++) - { itr_1 = r[i].begin(); - while(itr_1 != r[i].end()) - { j = *itr_1++; - CPPAD_ASSERT_KNOWN( - j < q, - "RevSparseJac: transpose is true and element of the set\n" - "r[i] has value greater than or equal q." - ); - CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - var_sparsity.add_element( dep_taddr_[i], j ); - } - } - } - else - { for(i = 0; i < q; i++) - { itr_1 = r[i].begin(); - while(itr_1 != r[i].end()) - { j = *itr_1++; - CPPAD_ASSERT_KNOWN( - j < m, - "RevSparseJac: transpose is false and element of the set\n" - "r[i] has value greater than or equal range dimension." - ); - CPPAD_ASSERT_UNKNOWN( dep_taddr_[j] < num_var_tape_ ); - var_sparsity.add_element( dep_taddr_[j], i ); - } - } - } - // evaluate the sparsity patterns - local::RevJacSweep( - dependency, - n, - num_var_tape_, - &play_, - var_sparsity - ); - - // return values corresponding to dependent variables - CPPAD_ASSERT_UNKNOWN( size_t(s.size()) == q || transpose ); - CPPAD_ASSERT_UNKNOWN( size_t(s.size()) == n || ! transpose ); - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] == (j+1) ); - - // ind_taddr_[j] is operator taddr for j-th independent variable - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == local::InvOp ); - - CPPAD_ASSERT_UNKNOWN( var_sparsity.end() == q ); - local::sparse_list::const_iterator itr_2(var_sparsity, j+1); - i = *itr_2; - while( i < q ) - { if( transpose ) - s[j].insert(i); - else s[i].insert(j); - i = *(++itr_2); - } - } -} - -// ========================================================================= -// RevSparseJac -/*! -User API for Jacobian sparsity patterns using reverse mode. - -The C++ source code corresponding to this operation is -\verbatim - s = f.RevSparseJac(q, r, transpose, dependency) -\endverbatim - -\tparam Base -is the base type for this recording. - -\tparam VectorSet -is a simple vector with elements of type \c bool. -or \c std::set. - -\param q -is the number of rows in the matrix \f$ R \f$. - -\param r -is a sparsity pattern for the matrix \f$ R \f$. - -\param transpose -are the sparsity patterns for \f$ R \f$ and \f$ S(x) \f$ transposed. - -\param dependency -Are the derivatives with respect to left and right of the expression below -considered to be non-zero: -\code - CondExpRel(left, right, if_true, if_false) -\endcode -This is used by the optimizer to obtain the correct dependency relations. - - -\return -If \c transpose is false (true), the return value is a sparsity pattern -for \f$ S(x) \f$ (\f$ S(x)^T \f$) where -\f[ - S(x) = R * F^{(1)} (x) -\f] -and \f$ F \f$ is the function corresponding to the operation sequence -and \a x is any argument value. -If \c VectorSet::value_type is \c bool, -the return value has size \f$ q * n \f$ ( \f$ n * q \f$). -If \c VectorSet::value_type is \c std::set, -the return value has size \f$ q \f$ ( \f$ n \f$) -and with all its elements between zero and \f$ n - 1 \f$ (\f$ q - 1 \f$). -*/ -template -template -VectorSet ADFun::RevSparseJac( - size_t q , - const VectorSet& r , - bool transpose , - bool dependency ) -{ - VectorSet s; - typedef typename VectorSet::value_type Set_type; - - RevSparseJacCase( - Set_type() , - transpose , - dependency , - q , - r , - s - ); - return s; -} -// =========================================================================== -// RevSparseJacCheckpoint -/*! -Reverse mode Jacobian sparsity calculation used by checkpoint functions. - -\tparam Base -is the base type for this recording. - -\param transpose -is true (false) s is equal to \f$ S(x) \f$ (\f$ S(x)^T \f$) -where -\f[ - S(x) = R * F^{(1)} (x) -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \f$ x \f$ is any argument value. - -\param q -is the number of rows in the matrix \f$ R \f$. - -\param r -is a sparsity pattern for the matrix \f$ R \f$. - -\param transpose -are the sparsity patterns for \f$ R \f$ and \f$ S(x) \f$ transposed. - -\param dependency -Are the derivatives with respect to left and right of the expression below -considered to be non-zero: -\code - CondExpRel(left, right, if_true, if_false) -\endcode -This is used by the optimizer to obtain the correct dependency relations. - -\param s -The input size and elements of s do not matter. -On output, s is the sparsity pattern for the matrix \f$ S(x) \f$ -or \f$ S(x)^T \f$ depending on transpose. - -*/ -template -void ADFun::RevSparseJacCheckpoint( - size_t q , - const local::sparse_list& r , - bool transpose , - bool dependency , - local::sparse_list& s ) -{ size_t n = Domain(); - size_t m = Range(); - -# ifndef NDEBUG - if( transpose ) - { CPPAD_ASSERT_UNKNOWN( r.n_set() == m ); - CPPAD_ASSERT_UNKNOWN( r.end() == q ); - } - else - { CPPAD_ASSERT_UNKNOWN( r.n_set() == q ); - CPPAD_ASSERT_UNKNOWN( r.end() == m ); - } - for(size_t i = 0; i < m; i++) - CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); -# endif - - // holds reverse Jacobian sparsity pattern for all variables - local::sparse_list var_sparsity; - var_sparsity.resize(num_var_tape_, q); - - // set sparsity pattern for dependent variables - if( transpose ) - { for(size_t i = 0; i < m; i++) - { local::sparse_list::const_iterator itr(r, i); - size_t j = *itr; - while( j < q ) - { var_sparsity.add_element( dep_taddr_[i], j ); - j = *(++itr); - } - } - } - else - { for(size_t j = 0; j < q; j++) - { local::sparse_list::const_iterator itr(r, j); - size_t i = *itr; - while( i < m ) - { var_sparsity.add_element( dep_taddr_[i], j ); - i = *(++itr); - } - } - } - - // evaluate the sparsity pattern for all variables - local::RevJacSweep( - dependency, - n, - num_var_tape_, - &play_, - var_sparsity - ); - - // dimension the return value - if( transpose ) - s.resize(n, m); - else - s.resize(m, n); - - // return values corresponding to independent variables - for(size_t j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] == (j+1) ); - - // ind_taddr_[j] is operator taddr for j-th independent variable - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == local::InvOp ); - - // extract the result from var_sparsity - CPPAD_ASSERT_UNKNOWN( var_sparsity.end() == q ); - local::sparse_list::const_iterator itr(var_sparsity, j+1); - size_t i = *itr; - while( i < q ) - { if( transpose ) - s.add_element(j, i); - else - s.add_element(i, j); - i = *(++itr); - } - } - -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/rev_two.hpp b/ct_core/include/ct/external/cppad/core/rev_two.hpp deleted file mode 100644 index 933d578e2..000000000 --- a/ct_core/include/ct/external/cppad/core/rev_two.hpp +++ /dev/null @@ -1,236 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_REV_TWO_HPP -# define CPPAD_CORE_REV_TWO_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin RevTwo$$ -$spell - ddw - typename - Taylor - const -$$ - - - - - -$section Reverse Mode Second Partial Derivative Driver$$ -$mindex order easy$$ - -$head Syntax$$ -$icode%ddw% = %f%.RevTwo(%x%, %i%, %j%)%$$ - - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -The syntax above sets -$latex \[ - ddw [ k * p + \ell ] - = - \DD{ F_{i[ \ell ]} }{ x_{j[ \ell ]} }{ x_k } (x) -\] $$ -for $latex k = 0 , \ldots , n-1$$ -and $latex \ell = 0 , \ldots , p$$, -where $latex p$$ is the size of the vectors $icode i$$ and $icode j$$. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/RevTwo Uses Forward/RevTwo/RevTwo Uses Forward/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %VectorBase% &%x% -%$$ -(see $cref/VectorBase/RevTwo/VectorBase/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the partial derivatives listed above. - -$head i$$ -The argument $icode i$$ has prototype -$codei% - const %VectorSize_t% &%i% -%$$ -(see $cref/VectorSize_t/RevTwo/VectorSize_t/$$ below) -We use $icode p$$ to denote the size of the vector $icode i$$. -All of the indices in $icode i$$ -must be less than $icode m$$, the dimension of the -$cref/range/seq_property/Range/$$ space for $icode f$$; i.e., -for $latex \ell = 0 , \ldots , p-1$$, $latex i[ \ell ] < m$$. - -$head j$$ -The argument $icode j$$ has prototype -$codei% - const %VectorSize_t% &%j% -%$$ -(see $cref/VectorSize_t/RevTwo/VectorSize_t/$$ below) -and its size must be equal to $icode p$$, -the size of the vector $icode i$$. -All of the indices in $icode j$$ -must be less than $icode n$$; i.e., -for $latex \ell = 0 , \ldots , p-1$$, $latex j[ \ell ] < n$$. - -$head ddw$$ -The result $icode ddw$$ has prototype -$codei% - %VectorBase% %ddw% -%$$ -(see $cref/VectorBase/RevTwo/VectorBase/$$ below) -and its size is $latex n * p$$. -It contains the requested partial derivatives; to be specific, -for $latex k = 0 , \ldots , n - 1 $$ -and $latex \ell = 0 , \ldots , p - 1$$ -$latex \[ - ddw [ k * p + \ell ] - = - \DD{ F_{i[ \ell ]} }{ x_{j[ \ell ]} }{ x_k } (x) -\] $$ - -$head VectorBase$$ -The type $icode VectorBase$$ must be a $cref SimpleVector$$ class with -$cref/elements of type Base/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head VectorSize_t$$ -The type $icode VectorSize_t$$ must be a $cref SimpleVector$$ class with -$cref/elements of type size_t/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head RevTwo Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to $code RevTwo$$, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0, %x%)%$$ -and the other coefficients are unspecified. - -$head Examples$$ -$children% - example/rev_two.cpp -%$$ -The routine -$cref/RevTwo/rev_two.cpp/$$ is both an example and test. -It returns $code true$$, if it succeeds and $code false$$ otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -template -VectorBase ADFun::RevTwo( - const VectorBase &x, - const VectorSize_t &i, - const VectorSize_t &j) -{ size_t i1; - size_t j1; - size_t k; - size_t l; - - size_t n = Domain(); - size_t m = Range(); - size_t p = i.size(); - - // check VectorBase is Simple Vector class with Base elements - CheckSimpleVector(); - - // check VectorSize_t is Simple Vector class with size_t elements - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( - x.size() == n, - "RevTwo: Length of x not equal domain dimension for f." - ); - CPPAD_ASSERT_KNOWN( - i.size() == j.size(), - "RevTwo: Lenght of the i and j vectors are not equal." - ); - // point at which we are evaluating the second partials - Forward(0, x); - - // dimension the return value - VectorBase ddw(n * p); - - // direction vector in argument space - VectorBase dx(n); - for(j1 = 0; j1 < n; j1++) - dx[j1] = Base(0); - - // direction vector in range space - VectorBase w(m); - for(i1 = 0; i1 < m; i1++) - w[i1] = Base(0); - - // place to hold the results of a reverse calculation - VectorBase r(n * 2); - - // check the indices in i and j - for(l = 0; l < p; l++) - { i1 = i[l]; - j1 = j[l]; - CPPAD_ASSERT_KNOWN( - i1 < m, - "RevTwo: an eleemnt of i not less than range dimension for f." - ); - CPPAD_ASSERT_KNOWN( - j1 < n, - "RevTwo: an element of j not less than domain dimension for f." - ); - } - - // loop over all forward directions - for(j1 = 0; j1 < n; j1++) - { // first order forward mode calculation done - bool first_done = false; - for(l = 0; l < p; l++) if( j[l] == j1 ) - { if( ! first_done ) - { first_done = true; - - // first order forward mode in j1 direction - dx[j1] = Base(1); - Forward(1, dx); - dx[j1] = Base(0); - } - // execute a reverse in this component direction - i1 = i[l]; - w[i1] = Base(1); - r = Reverse(2, w); - w[i1] = Base(0); - - // place the reverse result in return value - for(k = 0; k < n; k++) - ddw[k * p + l] = r[k * 2 + 1]; - } - } - return ddw; -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/reverse.hpp b/ct_core/include/ct/external/cppad/core/reverse.hpp deleted file mode 100644 index 17885456a..000000000 --- a/ct_core/include/ct/external/cppad/core/reverse.hpp +++ /dev/null @@ -1,209 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_REVERSE_HPP -# define CPPAD_CORE_REVERSE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file reverse.hpp -Compute derivatives using reverse mode. -*/ - - -/*! -Use reverse mode to compute derivative of forward mode Taylor coefficients. - -The function -\f$ X : {\rm R} \times {\rm R}^{n \times q} \rightarrow {\rm R} \f$ -is defined by -\f[ -X(t , u) = \sum_{k=0}^{q-1} u^{(k)} t^k -\f] -The function -\f$ Y : {\rm R} \times {\rm R}^{n \times q} \rightarrow {\rm R} \f$ -is defined by -\f[ -Y(t , u) = F[ X(t, u) ] -\f] -The function -\f$ W : {\rm R}^{n \times q} \rightarrow {\rm R} \f$ is defined by -\f[ -W(u) = \sum_{k=0}^{q-1} ( w^{(k)} )^{\rm T} -\frac{1}{k !} \frac{ \partial^k } { t^k } Y(0, u) -\f] - -\tparam Base -base type for the operator; i.e., this operation sequence was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\tparam VectorBase -is a Simple Vector class with elements of type \a Base. - -\param q -is the number of the number of Taylor coefficients that are being -differentiated (per variable). - -\param w -is the weighting for each of the Taylor coefficients corresponding -to dependent variables. -If the argument \a w has size m * q , -for \f$ k = 0 , \ldots , q-1 \f$ and \f$ i = 0, \ldots , m-1 \f$, -\f[ - w_i^{(k)} = w [ i * q + k ] -\f] -If the argument \a w has size \c m , -for \f$ k = 0 , \ldots , q-1 \f$ and \f$ i = 0, \ldots , m-1 \f$, -\f[ -w_i^{(k)} = \left\{ \begin{array}{ll} - w [ i ] & {\rm if} \; k = q-1 - \\ - 0 & {\rm otherwise} -\end{array} \right. -\f] - -\return -Is a vector \f$ dw \f$ such that -for \f$ j = 0 , \ldots , n-1 \f$ and -\f$ k = 0 , \ldots , q-1 \f$ -\f[ - dw[ j * q + k ] = W^{(1)} ( x )_{j,k} -\f] -where the matrix \f$ x \f$ is the value for \f$ u \f$ -that corresponding to the forward mode Taylor coefficients -for the independent variables as specified by previous calls to Forward. - -*/ -template -template -VectorBase ADFun::Reverse(size_t q, const VectorBase &w) -{ // constants - const Base zero(0); - - // temporary indices - size_t i, j, k; - - // number of independent variables - size_t n = ind_taddr_.size(); - - // number of dependent variables - size_t m = dep_taddr_.size(); - - local::pod_vector Partial; - Partial.extend(num_var_tape_ * q); - - // update maximum memory requirement - // memoryMax = std::max( memoryMax, - // Memory() + num_var_tape_ * q * sizeof(Base) - // ); - - // check VectorBase is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( - size_t(w.size()) == m || size_t(w.size()) == (m * q), - "Argument w to Reverse does not have length equal to\n" - "the dimension of the range for the corresponding ADFun." - ); - CPPAD_ASSERT_KNOWN( - q > 0, - "The first argument to Reverse must be greater than zero." - ); - CPPAD_ASSERT_KNOWN( - num_order_taylor_ >= q, - "Less that q taylor_ coefficients are currently stored" - " in this ADFun object." - ); - // special case where multiple forward directions have been computed, - // but we are only using the one direction zero order results - if( (q == 1) & (num_direction_taylor_ > 1) ) - { num_order_taylor_ = 1; // number of orders to copy - size_t c = cap_order_taylor_; // keep the same capacity setting - size_t r = 1; // only keep one direction - capacity_order(c, r); - } - CPPAD_ASSERT_KNOWN( - num_direction_taylor_ == 1, - "Reverse mode for Forward(q, r, xq) with more than one direction" - "\n(r > 1) is not yet supported for q > 1." - ); - // initialize entire Partial matrix to zero - for(i = 0; i < num_var_tape_; i++) - for(j = 0; j < q; j++) - Partial[i * q + j] = zero; - - // set the dependent variable direction - // (use += because two dependent variables can point to same location) - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - if( size_t(w.size()) == m ) - Partial[dep_taddr_[i] * q + q - 1] += w[i]; - else - { for(k = 0; k < q; k++) - // ? should use += here, first make test to demonstrate bug - Partial[ dep_taddr_[i] * q + k ] = w[i * q + k ]; - } - } - - // evaluate the derivatives - CPPAD_ASSERT_UNKNOWN( cskip_op_.size() == play_.num_op_rec() ); - CPPAD_ASSERT_UNKNOWN( load_op_.size() == play_.num_load_op_rec() ); - local::ReverseSweep( - q - 1, - n, - num_var_tape_, - &play_, - cap_order_taylor_, - taylor_.data(), - q, - Partial.data(), - cskip_op_.data(), - load_op_ - ); - - // return the derivative values - VectorBase value(n * q); - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] < num_var_tape_ ); - - // independent variable taddr equals its operator taddr - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == local::InvOp ); - - // by the Reverse Identity Theorem - // partial of y^{(k)} w.r.t. u^{(0)} is equal to - // partial of y^{(q-1)} w.r.t. u^{(q - 1 - k)} - if( size_t(w.size()) == m ) - { for(k = 0; k < q; k++) - value[j * q + k ] = - Partial[ind_taddr_[j] * q + q - 1 - k]; - } - else - { for(k = 0; k < q; k++) - value[j * q + k ] = - Partial[ind_taddr_[j] * q + k]; - } - } - CPPAD_ASSERT_KNOWN( ! ( hasnan(value) && check_for_nan_ ) , - "dw = f.Reverse(q, w): has a nan,\n" - "but none of its Taylor coefficents are nan." - ); - - return value; -} - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/sign.hpp b/ct_core/include/ct/external/cppad/core/sign.hpp deleted file mode 100644 index 634647cf5..000000000 --- a/ct_core/include/ct/external/cppad/core/sign.hpp +++ /dev/null @@ -1,104 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_SIGN_HPP -# define CPPAD_CORE_SIGN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin sign$$ -$spell - CppAD - Dirac -$$ -$section The Sign: sign$$ - -$head Syntax$$ -$icode%y% = sign(%x%)%$$ - -$head Description$$ -Evaluates the $code sign$$ function which is defined by -$latex \[ -{\rm sign} (x) = -\left\{ \begin{array}{rl} - +1 & {\rm if} \; x > 0 \\ - 0 & {\rm if} \; x = 0 \\ - -1 & {\rm if} \; x < 0 -\end{array} \right. -\] $$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -CppAD computes the derivative of the $code sign$$ function as zero for all -argument values $icode x$$. -The correct mathematical derivative is different and -is given by -$latex \[ - {\rm sign}^{(1)} (x) = 2 \delta (x) -\] $$ -where $latex \delta (x)$$ is the Dirac Delta function. - -$head Example$$ -$children% - example/sign.cpp -%$$ -The file -$cref sign.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD AD::sign_me (void) const -{ - AD result; - result.value_ = sign(value_); - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - if( Variable(*this) ) - { // add this operation to the tape - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::SignOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::SignOp) == 1 ); - local::ADTape *tape = tape_this(); - - // corresponding operand address - tape->Rec_.PutArg(taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::SignOp); - // make result a variable - result.tape_id_ = tape->id_; - } - return result; -} - -template -inline AD sign(const AD &x) -{ return x.sign_me(); } - -template -inline AD sign(const VecAD_reference &x) -{ return x.ADBase().sign_me(); } - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/sparse.hpp b/ct_core/include/ct/external/cppad/core/sparse.hpp deleted file mode 100644 index 9d775b58e..000000000 --- a/ct_core/include/ct/external/cppad/core/sparse.hpp +++ /dev/null @@ -1,41 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_SPARSE_HPP -# define CPPAD_CORE_SPARSE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Sparse$$ -$spell -$$ - - -$section Calculating Sparsity Patterns$$ - -$childtable% - cppad/core/for_sparse_jac.hpp% - cppad/core/rev_sparse_jac.hpp% - example/dependency.cpp% - cppad/core/rev_sparse_hes.hpp% - cppad/core/for_sparse_hes.hpp% - example/bool_sparsity.cpp -%$$ - -$end -*/ - -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/core/sparse_hessian.hpp b/ct_core/include/ct/external/cppad/core/sparse_hessian.hpp deleted file mode 100644 index 061a71a24..000000000 --- a/ct_core/include/ct/external/cppad/core/sparse_hessian.hpp +++ /dev/null @@ -1,814 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_SPARSE_HESSIAN_HPP -# define CPPAD_CORE_SPARSE_HESSIAN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin sparse_hessian$$ -$spell - jacobian - recomputed - CppAD - valarray - std - Bool - hes - const - Taylor - cppad - cmake - colpack -$$ - -$section Sparse Hessian: Easy Driver$$ -$mindex SparseHessian$$ - -$head Syntax$$ -$icode%hes% = %f%.SparseHessian(%x%, %w%) -%hes% = %f%.SparseHessian(%x%, %w%, %p%) -%n_sweep% = %f%.SparseHessian(%x%, %w%, %p%, %row%, %col%, %hes%, %work%) -%$$ - -$head Purpose$$ -We use $latex n$$ for the $cref/domain/seq_property/Domain/$$ size, -and $latex m$$ for the $cref/range/seq_property/Range/$$ size of $icode f$$. -We use $latex F : \B{R}^n \rightarrow \B{R}^m$$ do denote the -$cref/AD function/glossary/AD Function/$$ -corresponding to $icode f$$. -The syntax above sets $icode hes$$ to the Hessian -$latex \[ - H(x) = \dpow{2}{x} \sum_{i=1}^m w_i F_i (x) -\] $$ -This routine takes advantage of the sparsity of the Hessian -in order to reduce the amount of computation necessary. -If $icode row$$ and $icode col$$ are present, it also takes -advantage of the reduced set of elements of the Hessian that -need to be computed. -One can use speed tests (e.g. $cref speed_test$$) -to verify that results are computed faster -than when using the routine $cref Hessian$$. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/Uses Forward/sparse_hessian/Uses Forward/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %VectorBase%& %x% -%$$ -(see $cref/VectorBase/sparse_hessian/VectorBase/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the Hessian. - -$head w$$ -The argument $icode w$$ has prototype -$codei% - const %VectorBase%& %w% -%$$ -and size $latex m$$. -It specifies the value of $latex w_i$$ in the expression -for $icode hes$$. -The more components of $latex w$$ that are identically zero, -the more sparse the resulting Hessian may be (and hence the more efficient -the calculation of $icode hes$$ may be). - -$head p$$ -The argument $icode p$$ is optional and has prototype -$codei% - const %VectorSet%& %p% -%$$ -(see $cref/VectorSet/sparse_hessian/VectorSet/$$ below) -If it has elements of type $code bool$$, -its size is $latex n * n$$. -If it has elements of type $code std::set$$, -its size is $latex n$$ and all its set elements are between -zero and $latex n - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the Hessian $latex H(x)$$. - -$subhead Purpose$$ -If this sparsity pattern does not change between calls to -$codei SparseHessian$$, it should be faster to calculate $icode p$$ once and -pass this argument to $codei SparseHessian$$. -If you specify $icode p$$, CppAD will use the same -type of sparsity representation -(vectors of $code bool$$ or vectors of $code std::set$$) -for its internal calculations. -Otherwise, the representation -for the internal calculations is unspecified. - -$subhead work$$ -If you specify $icode work$$ in the calling sequence, -it is not necessary to keep the sparsity pattern; see the heading -$cref/p/sparse_hessian/work/p/$$ under the $icode work$$ description. - -$subhead Column Subset$$ -If the arguments $icode row$$ and $icode col$$ are present, -and $cref/color_method/sparse_hessian/work/color_method/$$ is -$code cppad.general$$ or $code cppad.symmetric$$, -it is not necessary to compute the entire sparsity pattern. -Only the following subset of column values will matter: -$codei% - { %col%[%k%] : %k% = 0 , %...% , %K%-1 } -%$$. - - -$head row, col$$ -The arguments $icode row$$ and $icode col$$ are optional and have prototype -$codei% - const %VectorSize%& %row% - const %VectorSize%& %col% -%$$ -(see $cref/VectorSize/sparse_hessian/VectorSize/$$ below). -They specify which rows and columns of $latex H (x)$$ are -returned and in what order. -We use $latex K$$ to denote the value $icode%hes%.size()%$$ -which must also equal the size of $icode row$$ and $icode col$$. -Furthermore, -for $latex k = 0 , \ldots , K-1$$, it must hold that -$latex row[k] < n$$ and $latex col[k] < n$$. -In addition, -all of the $latex (row[k], col[k])$$ pairs must correspond to a true value -in the sparsity pattern $icode p$$. - -$head hes$$ -The result $icode hes$$ has prototype -$codei% - %VectorBase% %hes% -%$$ -In the case where $icode row$$ and $icode col$$ are not present, -the size of $icode hes$$ is $latex n * n$$ and -its size is $latex n * n$$. -In this case, for $latex i = 0 , \ldots , n - 1 $$ -and $latex ell = 0 , \ldots , n - 1$$ -$latex \[ - hes [ j * n + \ell ] = \DD{ w^{\rm T} F }{ x_j }{ x_\ell } ( x ) -\] $$ -$pre - -$$ -In the case where the arguments $icode row$$ and $icode col$$ are present, -we use $latex K$$ to denote the size of $icode hes$$. -The input value of its elements does not matter. -Upon return, for $latex k = 0 , \ldots , K - 1$$, -$latex \[ - hes [ k ] = \DD{ w^{\rm T} F }{ x_j }{ x_\ell } (x) - \; , \; - \; {\rm where} \; - j = row[k] - \; {\rm and } \; - \ell = col[k] -\] $$ - -$head work$$ -If this argument is present, it has prototype -$codei% - sparse_hessian_work& %work% -%$$ -This object can only be used with the routines $code SparseHessian$$. -During its the first use, information is stored in $icode work$$. -This is used to reduce the work done by future calls to $code SparseHessian$$ -with the same $icode f$$, $icode p$$, $icode row$$, and $icode col$$. -If a future call is made where any of these values have changed, -you must first call $icode%work%.clear()%$$ -to inform CppAD that this information needs to be recomputed. - -$subhead color_method$$ -The coloring algorithm determines which rows and columns -can be computed during the same sweep. -This field has prototype -$codei% - std::string %work%.color_method -%$$ -This value only matters on the first call to $code sparse_hessian$$ that -follows the $icode work$$ constructor or a call to -$icode%work%.clear()%$$. -$codei% - -"cppad.symmetric" -%$$ -This is the default coloring method (after a constructor or $code clear()$$). -It takes advantage of the fact that the Hessian matrix -is symmetric to find a coloring that requires fewer -$cref/sweeps/sparse_hessian/n_sweep/$$. -$codei% - -"cppad.general" -%$$ -This is the same as the $code "cppad"$$ method for the -$cref/sparse_jacobian/sparse_jacobian/work/color_method/$$ calculation. -$codei% - -"colpack.star" -%$$ -This method requires that -$cref colpack_prefix$$ was specified on the -$cref/cmake command/cmake/CMake Command/$$ line. -It also takes advantage of the fact that the Hessian matrix is symmetric. - -$subhead p$$ -If $icode work$$ is present, and it is not the first call after -its construction or a clear, -the sparsity pattern $icode p$$ is not used. -This enables one to free the sparsity pattern -and still compute corresponding sparse Hessians. - -$head n_sweep$$ -The return value $icode n_sweep$$ has prototype -$codei% - size_t %n_sweep% -%$$ -It is the number of first order forward sweeps -used to compute the requested Hessian values. -Each first forward sweep is followed by a second order reverse sweep -so it is also the number of reverse sweeps. -This is proportional to the total work that $code SparseHessian$$ does, -not counting the zero order forward sweep, -or the work to combine multiple columns into a single -forward-reverse sweep pair. - -$head VectorBase$$ -The type $icode VectorBase$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Base$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head VectorSet$$ -The type $icode VectorSet$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code bool$$ or $code std::set$$; -see $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for a discussion -of the difference. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$subhead Restrictions$$ -If $icode VectorSet$$ has elements of $code std::set$$, -then $icode%p%[%i%]%$$ must return a reference (not a copy) to the -corresponding set. -According to section 26.3.2.3 of the 1998 C++ standard, -$code std::valarray< std::set >$$ does not satisfy -this condition. - -$head VectorSize$$ -The type $icode VectorSize$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code size_t$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to any of the sparse Hessian routines, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0, %x%)%$$ -and the other coefficients are unspecified. - -$children% - example/sparse_hessian.cpp% - example/sub_sparse_hes.cpp% - example/sparse_sub_hes.cpp -%$$ - -$head Example$$ -The routine -$cref sparse_hessian.cpp$$ -is examples and tests of $code sparse_hessian$$. -It return $code true$$, if it succeeds and $code false$$ otherwise. - -$head Subset Hessian$$ -The routines -$cref sub_sparse_hes.cpp$$ and $cref sparse_sub_hes.cpp$$ -are examples and tests that compute a sparse Hessian -for a subset of the variables. -They return $code true$$, if they succeed and $code false$$ otherwise. - -$end ------------------------------------------------------------------------------ -*/ -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file sparse_hessian.hpp -Sparse Hessian driver routine and helper functions. -*/ -// =========================================================================== -/*! -class used by SparseHessian to hold information -so it does not need to be recomputed. -*/ -class sparse_hessian_work { - public: - /// Coloring method: "cppad", or "colpack" - /// (this field is set by user) - std::string color_method; - /// row and column indicies for return values - /// (some may be reflected by star coloring algorithm) - CppAD::vector row; - CppAD::vector col; - /// indices that sort the user row and col arrays by color - CppAD::vector order; - /// results of the coloring algorithm - CppAD::vector color; - - /// constructor - sparse_hessian_work(void) : color_method("cppad.symmetric") - { } - /// inform CppAD that this information needs to be recomputed - void clear(void) - { color_method = "cppad.symmetric"; - row.clear(); - col.clear(); - order.clear(); - color.clear(); - } -}; -// =========================================================================== -/*! -Private helper function that does computation for all Sparse Hessian cases. - -\tparam Base -is the base type for the recording that is stored in this ADFun. - -\tparam VectorSize -is sparse_pack or sparse_list. - -\param x [in] -is a vector specifing the point at which to compute the Hessian. - -\param w [in] -is the weighting vector that defines a scalar valued function by -a weighted sum of the components of the vector valued function -$latex F(x)$$. - -\param sparsity [in] -is the sparsity pattern for the Hessian that we are calculating. - -\param user_row [in] -is the vector of row indices for the returned Hessian values. - -\param user_col [in] -is the vector of columns indices for the returned Hessian values. -It must have the same size as user_row. - -\param hes [out] -is the vector of Hessian values. -It must have the same size as user_row. -The return value hes[k] is the second partial of -\f$ w^{\rm T} F(x)\f$ with respect to the -row[k] and col[k] component of \f$ x\f$. - -\param work -This structure contains information that is computed by \c SparseHessianCompute. -If the sparsity pattern, \c row vector, or \c col vectors -are not the same between calls to \c SparseHessianCompute, -\c work.clear() must be called to reinitialize \c work. - -\return -Is the number of first order forward sweeps used to compute the -requested Hessian values. -(This is also equal to the number of second order reverse sweeps.) -The total work, not counting the zero order -forward sweep, or the time to combine computations, is proportional to this -return value. -*/ -template -template -size_t ADFun::SparseHessianCompute( - const VectorBase& x , - const VectorBase& w , - VectorSet& sparsity , - const VectorSize& user_row , - const VectorSize& user_col , - VectorBase& hes , - sparse_hessian_work& work ) -{ - using CppAD::vectorBool; - size_t i, k, ell; - - CppAD::vector& row(work.row); - CppAD::vector& col(work.col); - CppAD::vector& color(work.color); - CppAD::vector& order(work.order); - - size_t n = Domain(); - - // some values - const Base zero(0); - const Base one(1); - - // check VectorBase is Simple Vector class with Base type elements - CheckSimpleVector(); - - // number of components of Hessian that are required - size_t K = hes.size(); - CPPAD_ASSERT_UNKNOWN( size_t( user_row.size() ) == K ); - CPPAD_ASSERT_UNKNOWN( size_t( user_col.size() ) == K ); - - CPPAD_ASSERT_UNKNOWN( size_t(x.size()) == n ); - CPPAD_ASSERT_UNKNOWN( color.size() == 0 || color.size() == n ); - CPPAD_ASSERT_UNKNOWN( row.size() == 0 || row.size() == K ); - CPPAD_ASSERT_UNKNOWN( col.size() == 0 || col.size() == K ); - - - // Point at which we are evaluating the Hessian - Forward(0, x); - - // check for case where nothing (except Forward above) to do - if( K == 0 ) - return 0; - - // Rows of the Hessian (i below) correspond to the forward mode index - // and columns (j below) correspond to the reverse mode index. - if( color.size() == 0 ) - { - CPPAD_ASSERT_UNKNOWN( sparsity.n_set() == n ); - CPPAD_ASSERT_UNKNOWN( sparsity.end() == n ); - - // copy user rwo and col to work space - row.resize(K); - col.resize(K); - for(k = 0; k < K; k++) - { row[k] = user_row[k]; - col[k] = user_col[k]; - } - - // execute coloring algorithm - color.resize(n); - if( work.color_method == "cppad.general" ) - local::color_general_cppad(sparsity, row, col, color); - else if( work.color_method == "cppad.symmetric" ) - local::color_symmetric_cppad(sparsity, row, col, color); - else if( work.color_method == "colpack.star" ) - { -# if CPPAD_HAS_COLPACK - local::color_symmetric_colpack(sparsity, row, col, color); -# else - CPPAD_ASSERT_KNOWN( - false, - "SparseHessian: work.color_method = colpack.star" - "and colpack_prefix missing from cmake command line." - ); -# endif - } - else - { CPPAD_ASSERT_KNOWN( - false, - "SparseHessian: work.color_method is not valid." - ); - } - - // put sorting indices in color order - VectorSize key(K); - order.resize(K); - for(k = 0; k < K; k++) - key[k] = color[ row[k] ]; - index_sort(key, order); - - } - size_t n_color = 1; - for(ell = 0; ell < n; ell++) if( color[ell] < n ) - n_color = std::max(n_color, color[ell] + 1); - - // direction vector for calls to forward (rows of the Hessian) - VectorBase u(n); - - // location for return values from reverse (columns of the Hessian) - VectorBase ddw(2 * n); - - // initialize the return value - for(k = 0; k < K; k++) - hes[k] = zero; - - // loop over colors - k = 0; - for(ell = 0; ell < n_color; ell++) - { CPPAD_ASSERT_UNKNOWN( color[ row[ order[k] ] ] == ell ); - - // combine all rows with this color - for(i = 0; i < n; i++) - { u[i] = zero; - if( color[i] == ell ) - u[i] = one; - } - // call forward mode for all these rows at once - Forward(1, u); - - // evaluate derivative of w^T * F'(x) * u - ddw = Reverse(2, w); - - // set the corresponding components of the result - while( k < K && color[ row[ order[k] ] ] == ell ) - { hes[ order[k] ] = ddw[ col[ order[k] ] * 2 + 1 ]; - k++; - } - } - return n_color; -} -// =========================================================================== -// Public Member Functions -// =========================================================================== -/*! -Compute user specified subset of a sparse Hessian. - -The C++ source code corresponding to this operation is -\verbatim - SparceHessian(x, w, p, row, col, hes, work) -\endverbatim - -\tparam Base -is the base type for the recording that is stored in this ADFun. - -\tparam VectorSize -is a simple vector class with elements of type \c size_t. - -\param x [in] -is a vector specifing the point at which to compute the Hessian. - -\param w [in] -is the weighting vector that defines a scalar valued function by -a weighted sum of the components of the vector valued function -$latex F(x)$$. - -\param p [in] -is the sparsity pattern for the Hessian that we are calculating. - -\param row [in] -is the vector of row indices for the returned Hessian values. - -\param col [in] -is the vector of columns indices for the returned Hessian values. -It must have the same size are r. - -\param hes [out] -is the vector of Hessian values. -It must have the same size are r. -The return value hes[k] is the second partial of -\f$ w^{\rm T} F(x)\f$ with respect to the -row[k] and col[k] component of \f$ x\f$. - -\param work -This structure contains information that is computed by \c SparseHessianCompute. -If the sparsity pattern, \c row vector, or \c col vectors -are not the same between calls to \c SparseHessian, -\c work.clear() must be called to reinitialize \c work. - -\return -Is the number of first order forward sweeps used to compute the -requested Hessian values. -(This is also equal to the number of second order reverse sweeps.) -The total work, not counting the zero order -forward sweep, or the time to combine computations, is proportional to this -return value. -*/ -template -template -size_t ADFun::SparseHessian( - const VectorBase& x , - const VectorBase& w , - const VectorSet& p , - const VectorSize& row , - const VectorSize& col , - VectorBase& hes , - sparse_hessian_work& work ) -{ - size_t n = Domain(); - size_t K = hes.size(); -# ifndef NDEBUG - size_t k; - CPPAD_ASSERT_KNOWN( - size_t(x.size()) == n , - "SparseHessian: size of x not equal domain dimension for f." - ); - CPPAD_ASSERT_KNOWN( - size_t(row.size()) == K && size_t(col.size()) == K , - "SparseHessian: either r or c does not have the same size as ehs." - ); - CPPAD_ASSERT_KNOWN( - work.color.size() == 0 || work.color.size() == n, - "SparseHessian: invalid value in work." - ); - for(k = 0; k < K; k++) - { CPPAD_ASSERT_KNOWN( - row[k] < n, - "SparseHessian: invalid value in r." - ); - CPPAD_ASSERT_KNOWN( - col[k] < n, - "SparseHessian: invalid value in c." - ); - } - if( work.color.size() != 0 ) - for(size_t j = 0; j < n; j++) CPPAD_ASSERT_KNOWN( - work.color[j] <= n, - "SparseHessian: invalid value in work." - ); -# endif - // check for case where there is nothing to compute - size_t n_sweep = 0; - if( K == 0 ) - return n_sweep; - - typedef typename VectorSet::value_type Set_type; - typedef typename local::internal_sparsity::pattern_type Pattern_type; - Pattern_type s; - if( work.color.size() == 0 ) - { bool transpose = false; - const char* error_msg = "SparseHessian: sparsity pattern" - " does not have proper row or column dimension"; - sparsity_user2internal(s, p, n, n, transpose, error_msg); - } - n_sweep = SparseHessianCompute(x, w, s, row, col, hes, work); - return n_sweep; -} -/*! -Compute a sparse Hessian. - -The C++ source code coresponding to this operation is -\verbatim - hes = SparseHessian(x, w, p) -\endverbatim - - -\tparam Base -is the base type for the recording that is stored in this -ADFun. - -\param x [in] -is a vector specifing the point at which to compute the Hessian. - -\param w [in] -The Hessian is computed for a weighted sum of the components -of the function corresponding to this ADFun object. -The argument \a w specifies the weights for each component. -It must have size equal to the range dimension for this ADFun object. - -\param p [in] -is a sparsity pattern for the Hessian. - -\return -Will be a vector of size \c n * n containing the Hessian of -at the point specified by \a x -(where \c n is the domain dimension for this ADFun object). -*/ -template -template -VectorBase ADFun::SparseHessian( - const VectorBase& x, const VectorBase& w, const VectorSet& p -) -{ size_t i, j, k; - - size_t n = Domain(); - VectorBase hes(n * n); - - CPPAD_ASSERT_KNOWN( - size_t(x.size()) == n, - "SparseHessian: size of x not equal domain size for f." - ); - - typedef typename VectorSet::value_type Set_type; - typedef typename local::internal_sparsity::pattern_type Pattern_type; - - // initialize the return value as zero - Base zero(0); - for(i = 0; i < n; i++) - for(j = 0; j < n; j++) - hes[i * n + j] = zero; - - // arguments to SparseHessianCompute - Pattern_type s; - CppAD::vector row; - CppAD::vector col; - sparse_hessian_work work; - bool transpose = false; - const char* error_msg = "SparseHessian: sparsity pattern" - " does not have proper row or column dimension"; - sparsity_user2internal(s, p, n, n, transpose, error_msg); - k = 0; - for(i = 0; i < n; i++) - { typename Pattern_type::const_iterator itr(s, i); - j = *itr; - while( j != s.end() ) - { row.push_back(i); - col.push_back(j); - k++; - j = *(++itr); - } - } - size_t K = k; - VectorBase H(K); - - // now we have folded this into the following case - SparseHessianCompute(x, w, s, row, col, H, work); - - // now set the non-zero return values - for(k = 0; k < K; k++) - hes[ row[k] * n + col[k] ] = H[k]; - - return hes; -} -/*! -Compute a sparse Hessian - -The C++ source code coresponding to this operation is -\verbatim - hes = SparseHessian(x, w) -\endverbatim - - -\tparam Base -is the base type for the recording that is stored in this -ADFun object. -The argument \a w specifies the weights for each component. -It must have size equal to the range dimension for this ADFun object. - -\return -Will be a vector of size \c n * n containing the Hessian of -at the point specified by \a x -(where \c n is the domain dimension for this ADFun object). -*/ -template -template -VectorBase ADFun::SparseHessian(const VectorBase &x, const VectorBase &w) -{ size_t i, j, k; - typedef CppAD::vectorBool VectorBool; - - size_t m = Range(); - size_t n = Domain(); - - // determine the sparsity pattern p for Hessian of w^T F - VectorBool r(n * n); - for(j = 0; j < n; j++) - { for(k = 0; k < n; k++) - r[j * n + k] = false; - r[j * n + j] = true; - } - ForSparseJac(n, r); - // - VectorBool s(m); - for(i = 0; i < m; i++) - s[i] = w[i] != 0; - VectorBool p = RevSparseHes(n, s); - - // compute sparse Hessian - return SparseHessian(x, w, p); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/sparse_jacobian.hpp b/ct_core/include/ct/external/cppad/core/sparse_jacobian.hpp deleted file mode 100644 index b0e48e11d..000000000 --- a/ct_core/include/ct/external/cppad/core/sparse_jacobian.hpp +++ /dev/null @@ -1,1088 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_SPARSE_JACOBIAN_HPP -# define CPPAD_CORE_SPARSE_JACOBIAN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// maximum number of sparse directions to compute at the same time - -// # define CPPAD_SPARSE_JACOBIAN_MAX_MULTIPLE_DIRECTION 1 -# define CPPAD_SPARSE_JACOBIAN_MAX_MULTIPLE_DIRECTION 64 - -/* -$begin sparse_jacobian$$ -$spell - cppad - colpack - cmake - recomputed - valarray - std - CppAD - Bool - jac - Jacobian - Jacobians - const - Taylor -$$ - -$section Sparse Jacobian: Easy Driver$$ -$mindex SparseJacobian$$ - -$head Syntax$$ -$icode%jac% = %f%.SparseJacobian(%x%) -%jac% = %f%.SparseJacobian(%x%, %p%) -%n_sweep% = %f%.SparseJacobianForward(%x%, %p%, %row%, %col%, %jac%, %work%) -%n_sweep% = %f%.SparseJacobianReverse(%x%, %p%, %row%, %col%, %jac%, %work%) -%$$ - -$head Purpose$$ -We use $latex n$$ for the $cref/domain/seq_property/Domain/$$ size, -and $latex m$$ for the $cref/range/seq_property/Range/$$ size of $icode f$$. -We use $latex F : \B{R}^n \rightarrow \B{R}^m$$ do denote the -$cref/AD function/glossary/AD Function/$$ -corresponding to $icode f$$. -The syntax above sets $icode jac$$ to the Jacobian -$latex \[ - jac = F^{(1)} (x) -\] $$ -This routine takes advantage of the sparsity of the Jacobian -in order to reduce the amount of computation necessary. -If $icode row$$ and $icode col$$ are present, it also takes -advantage of the reduced set of elements of the Jacobian that -need to be computed. -One can use speed tests (e.g. $cref speed_test$$) -to verify that results are computed faster -than when using the routine $cref Jacobian$$. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/Uses Forward/sparse_jacobian/Uses Forward/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %VectorBase%& %x% -%$$ -(see $cref/VectorBase/sparse_jacobian/VectorBase/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the Jacobian. - -$head p$$ -The argument $icode p$$ is optional and has prototype -$codei% - const %VectorSet%& %p% -%$$ -(see $cref/VectorSet/sparse_jacobian/VectorSet/$$ below). -If it has elements of type $code bool$$, -its size is $latex m * n$$. -If it has elements of type $code std::set$$, -its size is $latex m$$ and all its set elements are between -zero and $latex n - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the Jacobian $latex F^{(1)} (x)$$. -$pre - -$$ -If this sparsity pattern does not change between calls to -$codei SparseJacobian$$, it should be faster to calculate $icode p$$ once -(using $cref ForSparseJac$$ or $cref RevSparseJac$$) -and then pass $icode p$$ to $codei SparseJacobian$$. -Furthermore, if you specify $icode work$$ in the calling sequence, -it is not necessary to keep the sparsity pattern; see the heading -$cref/p/sparse_jacobian/work/p/$$ under the $icode work$$ description. -$pre - -$$ -In addition, -if you specify $icode p$$, CppAD will use the same -type of sparsity representation -(vectors of $code bool$$ or vectors of $code std::set$$) -for its internal calculations. -Otherwise, the representation -for the internal calculations is unspecified. - -$head row, col$$ -The arguments $icode row$$ and $icode col$$ are optional and have prototype -$codei% - const %VectorSize%& %row% - const %VectorSize%& %col% -%$$ -(see $cref/VectorSize/sparse_jacobian/VectorSize/$$ below). -They specify which rows and columns of $latex F^{(1)} (x)$$ are -computes and in what order. -Not all the non-zero entries in $latex F^{(1)} (x)$$ need be computed, -but all the entries specified by $icode row$$ and $icode col$$ -must be possibly non-zero in the sparsity pattern. -We use $latex K$$ to denote the value $icode%jac%.size()%$$ -which must also equal the size of $icode row$$ and $icode col$$. -Furthermore, -for $latex k = 0 , \ldots , K-1$$, it must hold that -$latex row[k] < m$$ and $latex col[k] < n$$. - -$head jac$$ -The result $icode jac$$ has prototype -$codei% - %VectorBase%& %jac% -%$$ -In the case where the arguments $icode row$$ and $icode col$$ are not present, -the size of $icode jac$$ is $latex m * n$$ and -for $latex i = 0 , \ldots , m-1$$, -$latex j = 0 , \ldots , n-1$$, -$latex \[ - jac [ i * n + j ] = \D{ F_i }{ x_j } (x) -\] $$ -$pre - -$$ -In the case where the arguments $icode row$$ and $icode col$$ are present, -we use $latex K$$ to denote the size of $icode jac$$. -The input value of its elements does not matter. -Upon return, for $latex k = 0 , \ldots , K - 1$$, -$latex \[ - jac [ k ] = \D{ F_i }{ x_j } (x) - \; , \; - \; {\rm where} \; - i = row[k] - \; {\rm and } \; - j = col[k] -\] $$ - -$head work$$ -If this argument is present, it has prototype -$codei% - sparse_jacobian_work& %work% -%$$ -This object can only be used with the routines -$code SparseJacobianForward$$ and $code SparseJacobianReverse$$. -During its the first use, information is stored in $icode work$$. -This is used to reduce the work done by future calls to the same mode -(forward or reverse), -the same $icode f$$, $icode p$$, $icode row$$, and $icode col$$. -If a future call is for a different mode, -or any of these values have changed, -you must first call $icode%work%.clear()%$$ -to inform CppAD that this information needs to be recomputed. - -$subhead color_method$$ -The coloring algorithm determines which columns (forward mode) -or rows (reverse mode) can be computed during the same sweep. -This field has prototype -$codep% - std::string %work%.color_method -%$$ -and its default value (after a constructor or $code clear()$$) -is $code "cppad"$$. -If $cref colpack_prefix$$ is specified on the -$cref/cmake command/cmake/CMake Command/$$ line, -you can set this method to $code "colpack"$$. -This value only matters on the first call to $code sparse_jacobian$$ -that follows the $icode work$$ constructor or a call to -$icode%work%.clear()%$$. - -$subhead p$$ -If $icode work$$ is present, and it is not the first call after -its construction or a clear, -the sparsity pattern $icode p$$ is not used. -This enables one to free the sparsity pattern -and still compute corresponding sparse Jacobians. - -$head n_sweep$$ -The return value $icode n_sweep$$ has prototype -$codei% - size_t %n_sweep% -%$$ -If $code SparseJacobianForward$$ ($code SparseJacobianReverse$$) is used, -$icode n_sweep$$ is the number of first order forward (reverse) sweeps -used to compute the requested Jacobian values. -(This is also the number of colors determined by the coloring method -mentioned above). -This is proportional to the total work that $code SparseJacobian$$ does, -not counting the zero order forward sweep, -or the work to combine multiple columns (rows) into a single sweep. - -$head VectorBase$$ -The type $icode VectorBase$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Base$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head VectorSet$$ -The type $icode VectorSet$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code bool$$ or $code std::set$$; -see $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for a discussion -of the difference. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$subhead Restrictions$$ -If $icode VectorSet$$ has elements of $code std::set$$, -then $icode%p%[%i%]%$$ must return a reference (not a copy) to the -corresponding set. -According to section 26.3.2.3 of the 1998 C++ standard, -$code std::valarray< std::set >$$ does not satisfy -this condition. - -$head VectorSize$$ -The type $icode VectorSize$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code size_t$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to any of the sparse Jacobian routines, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0, %x%)%$$ -and the other coefficients are unspecified. - -After $code SparseJacobian$$, -the previous calls to $cref Forward$$ are undefined. - -$head Example$$ -$children% - example/sparse_jacobian.cpp -%$$ -The routine -$cref sparse_jacobian.cpp$$ -is examples and tests of $code sparse_jacobian$$. -It return $code true$$, if it succeeds and $code false$$ otherwise. - -$end -============================================================================== -*/ -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file sparse_jacobian.hpp -Sparse Jacobian driver routine and helper functions. -*/ -// =========================================================================== -/*! -class used by SparseJacobian to hold information so it does not need to be -recomputed. -*/ -class sparse_jacobian_work { - public: - /// Coloring method: "cppad", or "colpack" - /// (this field is set by user) - std::string color_method; - /// indices that sort the user row and col arrays by color - CppAD::vector order; - /// results of the coloring algorithm - CppAD::vector color; - - /// constructor - sparse_jacobian_work(void) : color_method("cppad") - { } - /// reset coloring method to its default and - /// inform CppAD that color and order need to be recomputed - void clear(void) - { color_method = "cppad"; - order.clear(); - color.clear(); - } -}; -// =========================================================================== -/*! -Private helper function forward mode cases - -\tparam Base -is the base type for the recording that is stored in this -ADFun object. - -\tparam VectorBase -is a simple vector class with elements of type \a Base. - -\tparam VectorSet -is either sparse_pack or sparse_list. - -\tparam VectorSize -is a simple vector class with elements of type \c size_t. - -\param x [in] -is a vector specifing the point at which to compute the Jacobian. - -\param p_transpose [in] -If work.color.size() != 0, -then \c p_transpose is not used. -Otherwise, it is a -sparsity pattern for the transpose of the Jacobian of this ADFun object. -Note that we do not change the values in \c p_transpose, -but is not \c const because we use its iterator facility. - -\param row [in] -is the vector of row indices for the returned Jacobian values. - -\param col [in] -is the vector of columns indices for the returned Jacobian values. -It must have the same size as \c row. - -\param jac [out] -is the vector of Jacobian values. We use \c K to denote the size of \c jac. -The return value jac[k] is the partial of the -row[k] range component of the function with respect -the the col[k] domain component of its argument. - -\param work -work.color_method is an input. The rest of -this structure contains information that is computed by \c SparseJacobainFor. -If the sparsity pattern, \c row vector, or \c col vectors -are not the same between calls to \c SparseJacobianFor, -\c work.clear() must be called to reinitialize \c work. - -\return -Is the number of first order forward sweeps used to compute the -requested Jacobian values. The total work, not counting the zero order -forward sweep, or the time to combine computations, is proportional to this -return value. -*/ -template -template -size_t ADFun::SparseJacobianFor( - const VectorBase& x , - VectorSet& p_transpose , - const VectorSize& row , - const VectorSize& col , - VectorBase& jac , - sparse_jacobian_work& work ) -{ - size_t j, k, ell; - - CppAD::vector& order(work.order); - CppAD::vector& color(work.color); - - size_t m = Range(); - size_t n = Domain(); - - // some values - const Base zero(0); - const Base one(1); - - // check VectorBase is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_UNKNOWN( size_t(x.size()) == n ); - CPPAD_ASSERT_UNKNOWN( color.size() == 0 || color.size() == n ); - - // number of components of Jacobian that are required - size_t K = size_t(jac.size()); - CPPAD_ASSERT_UNKNOWN( size_t( row.size() ) == K ); - CPPAD_ASSERT_UNKNOWN( size_t( col.size() ) == K ); - - // Point at which we are evaluating the Jacobian - Forward(0, x); - - // check for case where nothing (except Forward above) to do - if( K == 0 ) - return 0; - - if( color.size() == 0 ) - { - CPPAD_ASSERT_UNKNOWN( p_transpose.n_set() == n ); - CPPAD_ASSERT_UNKNOWN( p_transpose.end() == m ); - - // execute coloring algorithm - color.resize(n); - if( work.color_method == "cppad" ) - local::color_general_cppad(p_transpose, col, row, color); - else if( work.color_method == "colpack" ) - { -# if CPPAD_HAS_COLPACK - local::color_general_colpack(p_transpose, col, row, color); -# else - CPPAD_ASSERT_KNOWN( - false, - "SparseJacobianForward: work.color_method = colpack " - "and colpack_prefix missing from cmake command line." - ); -# endif - } - else CPPAD_ASSERT_KNOWN( - false, - "SparseJacobianForward: work.color_method is not valid." - ); - - // put sorting indices in color order - VectorSize key(K); - order.resize(K); - for(k = 0; k < K; k++) - key[k] = color[ col[k] ]; - index_sort(key, order); - } - size_t n_color = 1; - for(j = 0; j < n; j++) if( color[j] < n ) - n_color = std::max(n_color, color[j] + 1); - - // initialize the return value - for(k = 0; k < K; k++) - jac[k] = zero; - -# if CPPAD_SPARSE_JACOBIAN_MAX_MULTIPLE_DIRECTION == 1 - // direction vector and return values for calls to forward - VectorBase dx(n), dy(m); - - // loop over colors - k = 0; - for(ell = 0; ell < n_color; ell++) - { CPPAD_ASSERT_UNKNOWN( color[ col[ order[k] ] ] == ell ); - - // combine all columns with this color - for(j = 0; j < n; j++) - { dx[j] = zero; - if( color[j] == ell ) - dx[j] = one; - } - // call forward mode for all these columns at once - dy = Forward(1, dx); - - // set the corresponding components of the result - while( k < K && color[ col[order[k]] ] == ell ) - { jac[ order[k] ] = dy[row[order[k]]]; - k++; - } - } -# else - // abbreviation for this value - size_t max_r = CPPAD_SPARSE_JACOBIAN_MAX_MULTIPLE_DIRECTION; - CPPAD_ASSERT_UNKNOWN( max_r > 1 ); - - // count the number of colors done so far - size_t count_color = 0; - // count the sparse matrix entries done so far - k = 0; - while( count_color < n_color ) - { // number of colors we will do this time - size_t r = std::min(max_r , n_color - count_color); - VectorBase dx(n * r), dy(m * r); - - // loop over colors we will do this tme - for(ell = 0; ell < r; ell++) - { // combine all columns with this color - for(j = 0; j < n; j++) - { dx[j * r + ell] = zero; - if( color[j] == ell + count_color ) - dx[j * r + ell] = one; - } - } - size_t q = 1; - dy = Forward(q, r, dx); - - // store results - for(ell = 0; ell < r; ell++) - { // set the components of the result for this color - while( k < K && color[ col[order[k]] ] == ell + count_color ) - { jac[ order[k] ] = dy[ row[order[k]] * r + ell ]; - k++; - } - } - count_color += r; - } -# endif - return n_color; -} -/*! -Private helper function for reverse mode cases. - -\tparam Base -is the base type for the recording that is stored in this -ADFun object. - -\tparam VectorBase -is a simple vector class with elements of type \a Base. - -\tparam VectorSet -is either sparse_pack or sparse_list. - -\tparam VectorSize -is a simple vector class with elements of type \c size_t. - -\param x [in] -is a vector specifing the point at which to compute the Jacobian. - -\param p [in] -If work.color.size() != 0, then \c p is not used. -Otherwise, it is a -sparsity pattern for the Jacobian of this ADFun object. -Note that we do not change the values in \c p, -but is not \c const because we use its iterator facility. - -\param row [in] -is the vector of row indices for the returned Jacobian values. - -\param col [in] -is the vector of columns indices for the returned Jacobian values. -It must have the same size as \c row. - -\param jac [out] -is the vector of Jacobian values. -It must have the same size as \c row. -The return value jac[k] is the partial of the -row[k] range component of the function with respect -the the col[k] domain component of its argument. - -\param work -work.color_method is an input. The rest of -This structure contains information that is computed by \c SparseJacobainRev. -If the sparsity pattern, \c row vector, or \c col vectors -are not the same between calls to \c SparseJacobianRev, -\c work.clear() must be called to reinitialize \c work. - -\return -Is the number of first order reverse sweeps used to compute the -reverse Jacobian values. The total work, not counting the zero order -forward sweep, or the time to combine computations, is proportional to this -return value. -*/ -template -template -size_t ADFun::SparseJacobianRev( - const VectorBase& x , - VectorSet& p , - const VectorSize& row , - const VectorSize& col , - VectorBase& jac , - sparse_jacobian_work& work ) -{ - size_t i, k, ell; - - CppAD::vector& order(work.order); - CppAD::vector& color(work.color); - - size_t m = Range(); - size_t n = Domain(); - - // some values - const Base zero(0); - const Base one(1); - - // check VectorBase is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_UNKNOWN( size_t(x.size()) == n ); - CPPAD_ASSERT_UNKNOWN (color.size() == m || color.size() == 0 ); - - // number of components of Jacobian that are required - size_t K = size_t(jac.size()); - CPPAD_ASSERT_UNKNOWN( size_t( size_t( row.size() ) ) == K ); - CPPAD_ASSERT_UNKNOWN( size_t( size_t( col.size() ) ) == K ); - - // Point at which we are evaluating the Jacobian - Forward(0, x); - - // check for case where nothing (except Forward above) to do - if( K == 0 ) - return 0; - - if( color.size() == 0 ) - { - CPPAD_ASSERT_UNKNOWN( p.n_set() == m ); - CPPAD_ASSERT_UNKNOWN( p.end() == n ); - - // execute the coloring algorithm - color.resize(m); - if( work.color_method == "cppad" ) - local::color_general_cppad(p, row, col, color); - else if( work.color_method == "colpack" ) - { -# if CPPAD_HAS_COLPACK - local::color_general_colpack(p, row, col, color); -# else - CPPAD_ASSERT_KNOWN( - false, - "SparseJacobianReverse: work.color_method = colpack " - "and colpack_prefix missing from cmake command line." - ); -# endif - } - else CPPAD_ASSERT_KNOWN( - false, - "SparseJacobianReverse: work.color_method is not valid." - ); - - // put sorting indices in color order - VectorSize key(K); - order.resize(K); - for(k = 0; k < K; k++) - key[k] = color[ row[k] ]; - index_sort(key, order); - } - size_t n_color = 1; - for(i = 0; i < m; i++) if( color[i] < m ) - n_color = std::max(n_color, color[i] + 1); - - // weighting vector for calls to reverse - VectorBase w(m); - - // location for return values from Reverse - VectorBase dw(n); - - // initialize the return value - for(k = 0; k < K; k++) - jac[k] = zero; - - // loop over colors - k = 0; - for(ell = 0; ell < n_color; ell++) - { CPPAD_ASSERT_UNKNOWN( color[ row[ order[k] ] ] == ell ); - - // combine all the rows with this color - for(i = 0; i < m; i++) - { w[i] = zero; - if( color[i] == ell ) - w[i] = one; - } - // call reverse mode for all these rows at once - dw = Reverse(1, w); - - // set the corresponding components of the result - while( k < K && color[ row[order[k]] ] == ell ) - { jac[ order[k] ] = dw[col[order[k]]]; - k++; - } - } - return n_color; -} -// ========================================================================== -// Public Member functions -// ========================================================================== -/*! -Compute user specified subset of a sparse Jacobian using forward mode. - -The C++ source code corresponding to this operation is -\verbatim - SparceJacobianForward(x, p, row, col, jac, work) -\endverbatim - -\tparam Base -is the base type for the recording that is stored in this -ADFun object. - -\tparam VectorBase -is a simple vector class with elements of type \a Base. - -\tparam VectorSet -is a simple vector class with elements of type -\c bool or \c std::set. - -\tparam VectorSize -is a simple vector class with elements of type \c size_t. - -\param x [in] -is a vector specifing the point at which to compute the Jacobian. - -\param p [in] -is the sparsity pattern for the Jacobian that we are calculating. - -\param row [in] -is the vector of row indices for the returned Jacobian values. - -\param col [in] -is the vector of columns indices for the returned Jacobian values. -It must have the same size as \c row. - -\param jac [out] -is the vector of Jacobian values. -It must have the same size as \c row. -The return value jac[k] is the partial of the -row[k] range component of the function with respect -the the col[k] domain component of its argument. - -\param work [in,out] -this structure contains information that depends on the function object, -sparsity pattern, \c row vector, and \c col vector. -If they are not the same between calls to \c SparseJacobianForward, -\c work.clear() must be called to reinitialize them. - -\return -Is the number of first order forward sweeps used to compute the -requested Jacobian values. The total work, not counting the zero order -forward sweep, or the time to combine computations, is proportional to this -return value. -*/ -template -template -size_t ADFun::SparseJacobianForward( - const VectorBase& x , - const VectorSet& p , - const VectorSize& row , - const VectorSize& col , - VectorBase& jac , - sparse_jacobian_work& work ) -{ - size_t n = Domain(); - size_t m = Range(); - size_t K = jac.size(); -# ifndef NDEBUG - size_t k; - CPPAD_ASSERT_KNOWN( - size_t(x.size()) == n , - "SparseJacobianForward: size of x not equal domain dimension for f." - ); - CPPAD_ASSERT_KNOWN( - size_t(row.size()) == K && size_t(col.size()) == K , - "SparseJacobianForward: either r or c does not have " - "the same size as jac." - ); - CPPAD_ASSERT_KNOWN( - work.color.size() == 0 || work.color.size() == n, - "SparseJacobianForward: invalid value in work." - ); - for(k = 0; k < K; k++) - { CPPAD_ASSERT_KNOWN( - row[k] < m, - "SparseJacobianForward: invalid value in r." - ); - CPPAD_ASSERT_KNOWN( - col[k] < n, - "SparseJacobianForward: invalid value in c." - ); - } - if( work.color.size() != 0 ) - for(size_t j = 0; j < n; j++) CPPAD_ASSERT_KNOWN( - work.color[j] <= n, - "SparseJacobianForward: invalid value in work." - ); -# endif - // check for case where there is nothing to compute - size_t n_sweep = 0; - if( K == 0 ) - return n_sweep; - - typedef typename VectorSet::value_type Set_type; - typedef typename local::internal_sparsity::pattern_type Pattern_type; - Pattern_type s_transpose; - if( work.color.size() == 0 ) - { bool transpose = true; - const char* error_msg = "SparseJacobianForward: transposed sparsity" - " pattern does not have proper row or column dimension"; - sparsity_user2internal(s_transpose, p, n, m, transpose, error_msg); - } - n_sweep = SparseJacobianFor(x, s_transpose, row, col, jac, work); - return n_sweep; -} -/*! -Compute user specified subset of a sparse Jacobian using forward mode. - -The C++ source code corresponding to this operation is -\verbatim - SparceJacobianReverse(x, p, row, col, jac, work) -\endverbatim - -\tparam Base -is the base type for the recording that is stored in this -ADFun object. - -\tparam VectorBase -is a simple vector class with elements of type \a Base. - -\tparam VectorSet -is a simple vector class with elements of type -\c bool or \c std::set. - -\tparam VectorSize -is a simple vector class with elements of type \c size_t. - -\param x [in] -is a vector specifing the point at which to compute the Jacobian. - -\param p [in] -is the sparsity pattern for the Jacobian that we are calculating. - -\param row [in] -is the vector of row indices for the returned Jacobian values. - -\param col [in] -is the vector of columns indices for the returned Jacobian values. -It must have the same size as \c row. - -\param jac [out] -is the vector of Jacobian values. -It must have the same size as \c row. -The return value jac[k] is the partial of the -row[k] range component of the function with respect -the the col[k] domain component of its argument. - -\param work [in,out] -this structure contains information that depends on the function object, -sparsity pattern, \c row vector, and \c col vector. -If they are not the same between calls to \c SparseJacobianReverse, -\c work.clear() must be called to reinitialize them. - -\return -Is the number of first order reverse sweeps used to compute the -reverse Jacobian values. The total work, not counting the zero order -forward sweep, or the time to combine computations, is proportional to this -return value. -*/ -template -template -size_t ADFun::SparseJacobianReverse( - const VectorBase& x , - const VectorSet& p , - const VectorSize& row , - const VectorSize& col , - VectorBase& jac , - sparse_jacobian_work& work ) -{ - size_t m = Range(); - size_t n = Domain(); - size_t K = jac.size(); -# ifndef NDEBUG - size_t k; - CPPAD_ASSERT_KNOWN( - size_t(x.size()) == n , - "SparseJacobianReverse: size of x not equal domain dimension for f." - ); - CPPAD_ASSERT_KNOWN( - size_t(row.size()) == K && size_t(col.size()) == K , - "SparseJacobianReverse: either r or c does not have " - "the same size as jac." - ); - CPPAD_ASSERT_KNOWN( - work.color.size() == 0 || work.color.size() == m, - "SparseJacobianReverse: invalid value in work." - ); - for(k = 0; k < K; k++) - { CPPAD_ASSERT_KNOWN( - row[k] < m, - "SparseJacobianReverse: invalid value in r." - ); - CPPAD_ASSERT_KNOWN( - col[k] < n, - "SparseJacobianReverse: invalid value in c." - ); - } - if( work.color.size() != 0 ) - for(size_t i = 0; i < m; i++) CPPAD_ASSERT_KNOWN( - work.color[i] <= m, - "SparseJacobianReverse: invalid value in work." - ); -# endif - // check for case where there is nothing to compute - size_t n_sweep = 0; - if( K == 0 ) - return n_sweep; - - typedef typename VectorSet::value_type Set_type; - typedef typename local::internal_sparsity::pattern_type Pattern_type; - Pattern_type s; - if( work.color.size() == 0 ) - { bool transpose = false; - const char* error_msg = "SparseJacobianReverse: sparsity" - " pattern does not have proper row or column dimension"; - sparsity_user2internal(s, p, m, n, transpose, error_msg); - } - n_sweep = SparseJacobianRev(x, s, row, col, jac, work); - return n_sweep; -} -/*! -Compute a sparse Jacobian. - -The C++ source code corresponding to this operation is -\verbatim - jac = SparseJacobian(x, p) -\endverbatim - -\tparam Base -is the base type for the recording that is stored in this -ADFun object. - -\tparam VectorBase -is a simple vector class with elements of type \a Base. - -\tparam VectorSet -is a simple vector class with elements of type -\c bool or \c std::set. - -\param x [in] -is a vector specifing the point at which to compute the Jacobian. - -\param p [in] -is the sparsity pattern for the Jacobian that we are calculating. - -\return -Will be a vector if size \c m * n containing the Jacobian at the -specified point (in row major order). -*/ -template -template -VectorBase ADFun::SparseJacobian( - const VectorBase& x, const VectorSet& p -) -{ size_t i, j, k; - - size_t m = Range(); - size_t n = Domain(); - VectorBase jac(m * n); - - CPPAD_ASSERT_KNOWN( - size_t(x.size()) == n, - "SparseJacobian: size of x not equal domain size for f." - ); - CheckSimpleVector(); - - typedef typename VectorSet::value_type Set_type; - typedef typename local::internal_sparsity::pattern_type Pattern_type; - - // initialize the return value as zero - Base zero(0); - for(i = 0; i < m; i++) - for(j = 0; j < n; j++) - jac[i * n + j] = zero; - - sparse_jacobian_work work; - CppAD::vector row; - CppAD::vector col; - if( n <= m ) - { - // need an internal copy of sparsity pattern - Pattern_type s_transpose; - bool transpose = true; - const char* error_msg = "SparseJacobian: transposed sparsity" - " pattern does not have proper row or column dimension"; - sparsity_user2internal(s_transpose, p, n, m, transpose, error_msg); - - k = 0; - for(j = 0; j < n; j++) - { typename Pattern_type::const_iterator itr(s_transpose, j); - i = *itr; - while( i != s_transpose.end() ) - { row.push_back(i); - col.push_back(j); - k++; - i = *(++itr); - } - } - size_t K = k; - VectorBase J(K); - - // now we have folded this into the following case - SparseJacobianFor(x, s_transpose, row, col, J, work); - - // now set the non-zero return values - for(k = 0; k < K; k++) - jac[ row[k] * n + col[k] ] = J[k]; - } - else - { - // need an internal copy of sparsity pattern - Pattern_type s; - bool transpose = false; - const char* error_msg = "SparseJacobian: sparsity" - " pattern does not have proper row or column dimension"; - sparsity_user2internal(s, p, m, n, transpose, error_msg); - - k = 0; - for(i = 0; i < m; i++) - { typename Pattern_type::const_iterator itr(s, i); - j = *itr; - while( j != s.end() ) - { row.push_back(i); - col.push_back(j); - k++; - j = *(++itr); - } - } - size_t K = k; - VectorBase J(K); - - // now we have folded this into the following case - SparseJacobianRev(x, s, row, col, J, work); - - // now set the non-zero return values - for(k = 0; k < K; k++) - jac[ row[k] * n + col[k] ] = J[k]; - } - - return jac; -} - -/*! -Compute a sparse Jacobian. - -The C++ source code corresponding to this operation is -\verbatim - jac = SparseJacobian(x) -\endverbatim - -\tparam Base -is the base type for the recording that is stored in this -ADFun object. - -\tparam VectorBase -is a simple vector class with elements of the \a Base. - -\param x [in] -is a vector specifing the point at which to compute the Jacobian. - -\return -Will be a vector of size \c m * n containing the Jacobian at the -specified point (in row major order). -*/ -template -template -VectorBase ADFun::SparseJacobian( const VectorBase& x ) -{ typedef CppAD::vectorBool VectorBool; - - size_t m = Range(); - size_t n = Domain(); - - // sparsity pattern for Jacobian - VectorBool p(m * n); - - if( n <= m ) - { size_t j, k; - - // use forward mode - VectorBool r(n * n); - for(j = 0; j < n; j++) - { for(k = 0; k < n; k++) - r[j * n + k] = false; - r[j * n + j] = true; - } - p = ForSparseJac(n, r); - } - else - { size_t i, k; - - // use reverse mode - VectorBool s(m * m); - for(i = 0; i < m; i++) - { for(k = 0; k < m; k++) - s[i * m + k] = false; - s[i * m + i] = true; - } - p = RevSparseJac(m, s); - } - return SparseJacobian(x, p); -} - -} // END_CPPAD_NAMESPACE -# undef CPPAD_SPARSE_JACOBIAN_MAX_MULTIPLE_DIRECTION -# endif diff --git a/ct_core/include/ct/external/cppad/core/standard_math.hpp b/ct_core/include/ct/external/cppad/core/standard_math.hpp deleted file mode 100644 index 7efd7fdd6..000000000 --- a/ct_core/include/ct/external/cppad/core/standard_math.hpp +++ /dev/null @@ -1,132 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_STANDARD_MATH_HPP -# define CPPAD_CORE_STANDARD_MATH_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin unary_standard_math$$ -$spell - const - VecAD - fabs -$$ - -$section The Unary Standard Math Functions$$ - -$head Syntax$$ -$icode%y% = %fun%(%x%)%$$ - -$head Purpose$$ -Evaluates the standard math function $icode fun$$. - -$head Possible Types$$ - -$subhead Base$$ -If $icode Base$$ satisfies the -$cref/base type requirements/base_require/$$ -and argument $icode x$$ has prototype -$codei% - const %Base%& %x% -%$$ -then the result $icode y$$ has prototype -$codei% - %Base% %y% -%$$ - -$subhead AD$$ -If the argument $icode x$$ has prototype -$codei% - const AD<%Base%>& %x% -%$$ -then the result $icode y$$ has prototype -$codei% - AD<%Base%> %y% -%$$ - -$subhead VecAD$$ -If the argument $icode x$$ has prototype -$codei% - const VecAD<%Base%>::reference& %x% -%$$ -then the result $icode y$$ has prototype -$codei% - AD<%Base%> %y% -%$$ - -$children%cppad/core/std_math_98.hpp - %cppad/core/abs.hpp - %cppad/core/acosh.hpp - %cppad/core/asinh.hpp - %cppad/core/atanh.hpp - %cppad/core/erf.hpp - %cppad/core/expm1.hpp - %cppad/core/log1p.hpp - %cppad/core/sign.hpp -%$$ - -$head fun$$ -The possible values for $icode fun$$ are -$table -$icode fun$$ $pre $$ $cnext Description $rnext -$cref abs$$ $cnext $title abs$$ $rnext -$cref acos$$ $cnext $title acos$$ $rnext -$cref acosh$$ $cnext $title acosh$$ $rnext -$cref asin$$ $cnext $title asin$$ $rnext -$cref asinh$$ $cnext $title asinh$$ $rnext -$cref atan$$ $cnext $title atan$$ $rnext -$cref atanh$$ $cnext $title atanh$$ $rnext -$cref cos$$ $cnext $title cos$$ $rnext -$cref cosh$$ $cnext $title cosh$$ $rnext -$cref erf$$ $cnext $title erf$$ $rnext -$cref exp$$ $cnext $title exp$$ $rnext -$cref expm1$$ $cnext $title expm1$$ $rnext -$cref/fabs/abs/$$ $cnext $title abs$$ $rnext -$cref log10$$ $cnext $title log10$$ $rnext -$cref log1p$$ $cnext $title log1p$$ $rnext -$cref log$$ $cnext $title log$$ $rnext -$cref sign$$ $cnext $title sign$$ $rnext -$cref sin$$ $cnext $title sin$$ $rnext -$cref sinh$$ $cnext $title sinh$$ $rnext -$cref sqrt$$ $cnext $title sqrt$$ $rnext -$cref tan$$ $cnext $title tan$$ $rnext -$cref tanh$$ $cnext $title tanh$$ -$tend - -$end -*/ -# include -# include -# include -# include -# include -# include -# include -# include -# include - -/* -$begin binary_math$$ - -$section The Binary Math Functions$$ - -$childtable%cppad/core/atan2.hpp - %cppad/core/pow.hpp - %cppad/core/azmul.hpp -%$$ - -$end -*/ -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/core/std_math_98.hpp b/ct_core/include/ct/external/cppad/core/std_math_98.hpp deleted file mode 100644 index 3293d6024..000000000 --- a/ct_core/include/ct/external/cppad/core/std_math_98.hpp +++ /dev/null @@ -1,601 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_STD_MATH_98_HPP -# define CPPAD_CORE_STD_MATH_98_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -------------------------------------------------------------------------------- -$begin acos$$ -$spell - acos -$$ - -$section Inverse Sine Function: acos$$ - -$head Syntax$$ -$icode%y% = acos(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{acos}^{(1)} (x) & = & - (1 - x * x)^{-1/2} -\end{array} -\] $$ - -$head Example$$ -$children% - example/acos.cpp -%$$ -The file -$cref acos.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin asin$$ -$spell - asin -$$ - -$section Inverse Sine Function: asin$$ - -$head Syntax$$ -$icode%y% = asin(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{asin}^{(1)} (x) & = & (1 - x * x)^{-1/2} -\end{array} -\] $$ - -$head Example$$ -$children% - example/asin.cpp -%$$ -The file -$cref asin.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin atan$$ -$spell - atan -$$ - -$section Inverse Tangent Function: atan$$ - -$head Syntax$$ -$icode%y% = atan(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{atan}^{(1)} (x) & = & \frac{1}{1 + x^2} -\end{array} -\] $$ - -$head Example$$ -$children% - example/atan.cpp -%$$ -The file -$cref atan.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin cos$$ -$spell - cos -$$ - -$section The Cosine Function: cos$$ - -$head Syntax$$ -$icode%y% = cos(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{cos}^{(1)} (x) & = & - \sin(x) -\end{array} -\] $$ - -$head Example$$ -$children% - example/cos.cpp -%$$ -The file -$cref cos.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin cosh$$ -$spell - cosh -$$ - -$section The Hyperbolic Cosine Function: cosh$$ - -$head Syntax$$ -$icode%y% = cosh(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{cosh}^{(1)} (x) & = & \sinh(x) -\end{array} -\] $$ - -$head Example$$ -$children% - example/cosh.cpp -%$$ -The file -$cref cosh.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin exp$$ -$spell - exp -$$ - -$section The Exponential Function: exp$$ - -$head Syntax$$ -$icode%y% = exp(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{exp}^{(1)} (x) & = & \exp(x) -\end{array} -\] $$ - -$head Example$$ -$children% - example/exp.cpp -%$$ -The file -$cref exp.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin log$$ -$spell -$$ - -$section The Exponential Function: log$$ - -$head Syntax$$ -$icode%y% = log(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{log}^{(1)} (x) & = & \frac{1}{x} -\end{array} -\] $$ - -$head Example$$ -$children% - example/log.cpp -%$$ -The file -$cref log.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin log10$$ -$spell - CppAD -$$ - -$section The Base 10 Logarithm Function: log10$$ - -$head Syntax$$ -$icode%y% = log10(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Method$$ -CppAD uses the representation -$latex \[ -\begin{array}{lcr} - {\rm log10} (x) & = & \log(x) / \log(10) -\end{array} -\] $$ - -$head Example$$ -$children% - example/log10.cpp -%$$ -The file -$cref log10.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin sin$$ -$spell - sin -$$ - -$section The Sine Function: sin$$ - -$head Syntax$$ -$icode%y% = sin(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{sin}^{(1)} (x) & = & \cos(x) -\end{array} -\] $$ - -$head Example$$ -$children% - example/sin.cpp -%$$ -The file -$cref sin.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin sinh$$ -$spell - sinh -$$ - -$section The Hyperbolic Sine Function: sinh$$ - -$head Syntax$$ -$icode%y% = sinh(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{sinh}^{(1)} (x) & = & \cosh(x) -\end{array} -\] $$ - -$head Example$$ -$children% - example/sinh.cpp -%$$ -The file -$cref sinh.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin sqrt$$ -$spell - sqrt -$$ - -$section The Square Root Function: sqrt$$ - -$head Syntax$$ -$icode%y% = sqrt(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{sqrt}^{(1)} (x) & = & \frac{1}{2 \R{sqrt} (x) } -\end{array} -\] $$ - -$head Example$$ -$children% - example/sqrt.cpp -%$$ -The file -$cref sqrt.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin tan$$ -$spell - tan -$$ - -$section The Tangent Function: tan$$ - -$head Syntax$$ -$icode%y% = tan(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{tan}^{(1)} (x) & = & 1 + \tan (x)^2 -\end{array} -\] $$ - -$head Example$$ -$children% - example/tan.cpp -%$$ -The file -$cref tan.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin tanh$$ -$spell - tanh -$$ - -$section The Hyperbolic Tangent Function: tanh$$ - -$head Syntax$$ -$icode%y% = tanh(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{tanh}^{(1)} (x) & = & 1 - \tanh (x)^2 -\end{array} -\] $$ - -$head Example$$ -$children% - example/tanh.cpp -%$$ -The file -$cref tanh.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ - -/*! -\file std_math_98.hpp -Define AD standard math functions (using their Base versions) -*/ - -/*! -\def CPPAD_STANDARD_MATH_UNARY_AD(Name, Op) -Defines function Name with argument type AD and tape operation Op - -The macro defines the function x.Name() where x has type AD. -It then uses this funciton to define Name(x) where x has type -AD or VecAD_reference. - -If x is a variable, the tape unary operator Op is used -to record the operation and the result is identified as correspoding -to this operation; i.e., Name(x).taddr_ idendifies the operation and -Name(x).tape_id_ identifies the tape. - -This macro is used to define AD versions of -acos, asin, atan, cos, cosh, exp, fabs, log, sin, sinh, sqrt, tan, tanh. -*/ - -# define CPPAD_STANDARD_MATH_UNARY_AD(Name, Op) \ - template \ - inline AD Name(const AD &x) \ - { return x.Name##_me(); } \ - template \ - inline AD AD::Name##_me (void) const \ - { \ - AD result; \ - result.value_ = CppAD::Name(value_); \ - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); \ - \ - if( Variable(*this) ) \ - { CPPAD_ASSERT_UNKNOWN( NumArg(Op) == 1 ); \ - local::ADTape *tape = tape_this(); \ - tape->Rec_.PutArg(taddr_); \ - result.taddr_ = tape->Rec_.PutOp(Op); \ - result.tape_id_ = tape->id_; \ - } \ - return result; \ - } \ - template \ - inline AD Name(const VecAD_reference &x) \ - { return x.ADBase().Name##_me(); } - -// BEGIN CppAD namespace -namespace CppAD { - - CPPAD_STANDARD_MATH_UNARY_AD(acos, local::AcosOp) - CPPAD_STANDARD_MATH_UNARY_AD(asin, local::AsinOp) - CPPAD_STANDARD_MATH_UNARY_AD(atan, local::AtanOp) - CPPAD_STANDARD_MATH_UNARY_AD(cos, local::CosOp) - CPPAD_STANDARD_MATH_UNARY_AD(cosh, local::CoshOp) - CPPAD_STANDARD_MATH_UNARY_AD(exp, local::ExpOp) - CPPAD_STANDARD_MATH_UNARY_AD(fabs, local::AbsOp) - CPPAD_STANDARD_MATH_UNARY_AD(log, local::LogOp) - CPPAD_STANDARD_MATH_UNARY_AD(sin, local::SinOp) - CPPAD_STANDARD_MATH_UNARY_AD(sinh, local::SinhOp) - CPPAD_STANDARD_MATH_UNARY_AD(sqrt, local::SqrtOp) - CPPAD_STANDARD_MATH_UNARY_AD(tan, local::TanOp) - CPPAD_STANDARD_MATH_UNARY_AD(tanh, local::TanhOp) - -# if CPPAD_USE_CPLUSPLUS_2011 - CPPAD_STANDARD_MATH_UNARY_AD(asinh, local::AsinhOp) - CPPAD_STANDARD_MATH_UNARY_AD(acosh, local::AcoshOp) - CPPAD_STANDARD_MATH_UNARY_AD(atanh, local::AtanhOp) - CPPAD_STANDARD_MATH_UNARY_AD(expm1, local::Expm1Op) - CPPAD_STANDARD_MATH_UNARY_AD(log1p, local::Log1pOp) -# endif - -# if CPPAD_USE_CPLUSPLUS_2011 - // Error function is a special case - template - inline AD erf(const AD &x) - { return x.erf_me(); } - template - inline AD AD::erf_me (void) const - { - AD result; - result.value_ = CppAD::erf(value_); - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - if( Variable(*this) ) - { CPPAD_ASSERT_UNKNOWN( local::NumArg(local::ErfOp) == 3 ); - local::ADTape *tape = tape_this(); - // arg[0] = argument to erf function - tape->Rec_.PutArg(taddr_); - // arg[1] = zero - addr_t p = tape->Rec_.PutPar( Base(0) ); - tape->Rec_.PutArg(p); - // arg[2] = 2 / sqrt(pi) - p = tape->Rec_.PutPar(Base( - 1.0 / std::sqrt( std::atan(1.0) ) - )); - tape->Rec_.PutArg(p); - // - result.taddr_ = tape->Rec_.PutOp(local::ErfOp); - result.tape_id_ = tape->id_; - } - return result; - } - template - inline AD erf(const VecAD_reference &x) - { return x.ADBase().erf_me(); } -# endif - - /*! - Compute the log of base 10 of x where has type AD - - \tparam Base - is the base type (different from base for log) - for this AD type, see base_require. - - \param x - is the argument for the log10 function. - - \result - if the result is y, then \f$ x = 10^y \f$. - */ - template - inline AD log10(const AD &x) - { return CppAD::log(x) / CppAD::log( Base(10) ); } - template - inline AD log10(const VecAD_reference &x) - { return CppAD::log(x.ADBase()) / CppAD::log( Base(10) ); } -} - -# undef CPPAD_STANDARD_MATH_UNARY_AD - -# endif diff --git a/ct_core/include/ct/external/cppad/core/sub.hpp b/ct_core/include/ct/external/cppad/core/sub.hpp deleted file mode 100644 index 0a0f8503c..000000000 --- a/ct_core/include/ct/external/cppad/core/sub.hpp +++ /dev/null @@ -1,90 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_SUB_HPP -# define CPPAD_CORE_SUB_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD operator - (const AD &left , const AD &right) -{ - // compute the Base part - AD result; - result.value_ = left.value_ - right.value_; - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - // check if there is a recording in progress - local::ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return result; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = left.tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // result = variable - variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::SubvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::SubvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(left.taddr_, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::SubvvOp); - // make result a variable - result.tape_id_ = tape_id; - } - else if( IdenticalZero(right.value_) ) - { // result = variable - 0 - result.make_variable(left.tape_id_, left.taddr_); - } - else - { // result = variable - parameter - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::SubvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::SubvpOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(left.taddr_, p); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::SubvpOp); - // make result a variable - result.tape_id_ = tape_id; - } - } - else if( var_right ) - { // result = parameter - variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::SubpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::SubpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left.value_); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(local::SubpvOp); - // make result a variable - result.tape_id_ = tape_id; - } - return result; -} - -// convert other cases into the case above -CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR(-) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/sub_eq.hpp b/ct_core/include/ct/external/cppad/core/sub_eq.hpp deleted file mode 100644 index c9319aa77..000000000 --- a/ct_core/include/ct/external/cppad/core/sub_eq.hpp +++ /dev/null @@ -1,88 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_SUB_EQ_HPP -# define CPPAD_CORE_SUB_EQ_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD& AD::operator -= (const AD &right) -{ - // compute the Base part - Base left; - left = value_; - value_ -= right.value_; - - // check if there is a recording in progress - local::ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return *this; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // this = variable - variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::SubvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::SubvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(taddr_, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(local::SubvvOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - else if( IdenticalZero( right.value_ ) ) - { // this = variable - 0 - } - else - { // this = variable - parameter - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::SubvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::SubvpOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(taddr_, p); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(local::SubvpOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - } - else if( var_right ) - { // this = parameter - variable - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::SubpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::SubpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(local::SubpvOp); - // make this a variable - tape_id_ = tape_id; - } - return *this; -} - -CPPAD_FOLD_ASSIGNMENT_OPERATOR(-=) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/tape_link.hpp b/ct_core/include/ct/external/cppad/core/tape_link.hpp deleted file mode 100644 index ef3245f43..000000000 --- a/ct_core/include/ct/external/cppad/core/tape_link.hpp +++ /dev/null @@ -1,339 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_TAPE_LINK_HPP -# define CPPAD_CORE_TAPE_LINK_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include -# include -# include - -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file tape_link.hpp -Routines that Link AD and local::ADTape Objects. - -The routines that connect the AD class to the corresponding tapes -(one for each thread). -*/ - -/*! -Handle to the tape identifier for this AD class and the specific thread. - -\tparam Base -is the base type for this AD class. - -\param thread -is the thread number. The following condition must hold -\code -(! thread_alloc::in_parallel()) || thread == thread_alloc::thread_num() -\endcode - -\return -is a handle to the tape identifier for this thread -and AD class. -*/ -template -inline tape_id_t** AD::tape_id_handle(size_t thread) -{ CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static tape_id_t* tape_id_table[CPPAD_MAX_NUM_THREADS]; - CPPAD_ASSERT_UNKNOWN( - (! thread_alloc::in_parallel()) || thread == thread_alloc::thread_num() - ); - - return tape_id_table + thread; -} - -/*! -Pointer to the tape identifier for this AD class and the specific thread. - -\tparam Base -is the base type for this AD class. - -\param thread -is the thread number; i.e., -\code -thread == thread_alloc::thread_num() -\endcode -If this condition is not satisfied, and \c NDEBUG is not defined, -a CPPAD_ASSERT_UNKNOWN is generated. - -\return -is a pointer to the tape identifier for this thread -and AD class. - -\par Restrictions -This routine should only be called if there was a tape created -for the specified thread (it may no longer be recording). -*/ -template -inline tape_id_t* AD::tape_id_ptr(size_t thread) -{ CPPAD_ASSERT_UNKNOWN( *tape_id_handle(thread) != CPPAD_NULL ) - return *tape_id_handle(thread); -} - -/*! -Handle for the tape for this AD class and the specific thread. - -\tparam Base -is the base type for this AD class. - - -\param thread -is the thread number; i.e., -\code -thread == thread_alloc::thread_num() -\endcode -If this condition is not satisfied, and \c NDEBUG is not defined, -a CPPAD_ASSERT_UNKNOWN is generated. - -\return -is a handle for the AD class and the specified thread. -*/ -template -inline local::ADTape** AD::tape_handle(size_t thread) -{ CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static local::ADTape* tape_table[CPPAD_MAX_NUM_THREADS]; - CPPAD_ASSERT_UNKNOWN( thread == thread_alloc::thread_num() ); - - return tape_table + thread; -} - -/*! -Pointer for the tape for this AD class and the current thread. - -\code -thread == thread_alloc::thread_num() -\endcode - -\tparam Base -is the base type corresponding to AD operations. - -\return -is a pointer to the tape that is currently recording AD operations -for the current thread. -If this value is \c CPPAD_NULL, there is no tape currently -recording AD operations for this thread. -*/ -template -inline local::ADTape* AD::tape_ptr(void) -{ size_t thread = thread_alloc::thread_num(); - return *tape_handle(thread); -} - -/*! -Pointer for the tape for this AD class and the specified tape -identifier. - -\tparam Base -is the base type corresponding to AD operations. - -\param tape_id -is the identifier for the tape that is currently recording -AD operations for the current thread. -It must hold that the current thread is -\code - thread = size_t( tape_id % CPPAD_MAX_NUM_THREADS ) -\endcode -and that there is a tape recording AD operations -for this thread. -If this is not the currently executing thread, -a variable from a different thread is being recorded on the -tape for this thread which is a user error. - -\return -is a pointer to the tape that is currently recording AD operations -for the current thread (and it is not \c CPPAD_NULL). - -\par Restrictions -This routine should only be called if there is a tape recording operaitons -for the specified thread. -*/ -template -inline local::ADTape* AD::tape_ptr(tape_id_t tape_id) -{ size_t thread = size_t( tape_id % CPPAD_MAX_NUM_THREADS ); - CPPAD_ASSERT_KNOWN( - thread == thread_alloc::thread_num(), - "Attempt to use an AD variable with two different threads." - ); - CPPAD_ASSERT_UNKNOWN( tape_id == *tape_id_ptr(thread) ); - CPPAD_ASSERT_UNKNOWN( *tape_handle(thread) != CPPAD_NULL ); - return *tape_handle(thread); -} - -/*! -Create and delete tapes that record AD operations for current thread. - -\par thread -the current thread is given by -\code -thread = thread_alloc::thread_num() -\endcode - -\tparam Base -is the base type corresponding to AD operations. - -\param job -This argument determines if we are creating a new tape, or deleting an -old one. -- \c tape_manage_new : -Creates and a new tape. -It is assumed that there is no tape recording AD operations -for this thread when \c tape_manage is called. -It the input value of *tape_id_handle(thread) is \c CPPAD_NULL, -it will be changed to a non-zero pointer and the corresponding value -of *tape_id_ptr(thread) will be set to -thread + CPPAD_MAX_NUM_THREADS. -- \c tape_manage_delete : -It is assumed that there is a tape recording AD operations -for this thread when \c tape_manage is called. -The value of *tape_id_ptr(thread) will be advanced by -\c CPPAD_MAX_NUM_THREADS. - - -\return -- job == tape_manage_new: a pointer to the new tape is returned. -- job == tape_manage_delete: the value \c CPPAD_NULL is returned. -*/ -template -local::ADTape* AD::tape_manage(tape_manage_job job) -{ // this routine has static variables so first call cannot be in parallel - CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL - - // The tape for the master thread - static local::ADTape tape_zero; - - // Pointer to the tape for each thread - static local::ADTape* tape_table[CPPAD_MAX_NUM_THREADS]; - - // The id current being used for each of the tapes - static tape_id_t tape_id_save[CPPAD_MAX_NUM_THREADS]; - - // Thread corresponding to this call - size_t thread = thread_alloc::thread_num(); - - // tape_manage_clear - if( job == tape_manage_clear ) - { // This operation cannot be done in parallel - CPPAD_ASSERT_UNKNOWN(thread == 0 && (! thread_alloc::in_parallel())); - for(thread = 0; thread < CPPAD_MAX_NUM_THREADS; thread++) - { // if this thread has a tape - if( tape_table[thread] != CPPAD_NULL ) - { // id corresponding to this thread - tape_id_save[thread] = tape_table[thread]->id_; - *tape_id_handle(thread) = &tape_id_save[thread]; - - // delete all but the master thread - if( thread != 0 ) - delete( tape_table[thread] ); - - // set the tape pointer to null - tape_table[thread] = CPPAD_NULL; - } - } - return CPPAD_NULL; - } - - // id and tape fpor this thread - tape_id_t** tape_id = tape_id_handle(thread); - local::ADTape** tape = tape_handle(thread); - - // check if there is no tape currently attached to this thread - if( tape_table[thread] == CPPAD_NULL ) - { // allocate separate memroy to avoid false sharing - if( thread == 0 ) - { // mastert tape is a static in this routine - tape_table[thread] = &tape_zero; - } - else - { // other tapes are allocated - tape_table[thread] = new local::ADTape(); - } - // current id and pointer to this tape - tape_table[thread]->id_ = tape_id_save[thread]; - *tape_id = &tape_table[thread]->id_; - - // if id is zero, initialize it so that - // thread == tape id % CPPAD_MAX_NUM_THREADS - if( **tape_id == 0 ) - **tape_id = thread + CPPAD_MAX_NUM_THREADS; - } - // make sure tape_id_handle(thread) is pointing to the proper place - CPPAD_ASSERT_UNKNOWN( *tape_id == &tape_table[thread]->id_ ); - - // make sure tape_id value is valid for this thread - CPPAD_ASSERT_UNKNOWN( - size_t( **tape_id % CPPAD_MAX_NUM_THREADS ) == thread - ); - - switch(job) - { case tape_manage_new: - // tape for this thread must be null at the start - CPPAD_ASSERT_UNKNOWN( *tape == CPPAD_NULL ); - *tape = tape_table[thread]; - break; - - case tape_manage_delete: - CPPAD_ASSERT_UNKNOWN( *tape == tape_table[thread] ); - CPPAD_ASSERT_KNOWN( - std::numeric_limits::max() - - CPPAD_MAX_NUM_THREADS > **tape_id, - "To many different tapes given the type used for " - "CPPAD_TAPE_ID_TYPE" - ); - // advance tape identfier so all AD variables become parameters - **tape_id += CPPAD_MAX_NUM_THREADS; - // free memory corresponding to recording in the old tape - tape_table[thread]->Rec_.free(); - // inform rest of CppAD that no tape recording for this thread - *tape = CPPAD_NULL; - break; - - case tape_manage_clear: - CPPAD_ASSERT_UNKNOWN(false); - } - return *tape; -} - -/*! -Get a pointer to tape that records AD operations for the current thread. - -\tparam Base -is the base type corresponding to AD operations. - -\par thread -The current thread must be given by -\code - thread = this->tape_id_ % CPPAD_MAX_NUM_THREADS -\endcode - -\return -is a pointer to the tape that is currently recording AD operations -for the current thread. -This value must not be \c CPPAD_NULL; i.e., there must be a tape currently -recording AD operations for this thread. -*/ - -template -inline local::ADTape *AD::tape_this(void) const -{ - size_t thread = size_t( tape_id_ % CPPAD_MAX_NUM_THREADS ); - CPPAD_ASSERT_UNKNOWN( tape_id_ == *tape_id_ptr(thread) ); - CPPAD_ASSERT_UNKNOWN( *tape_handle(thread) != CPPAD_NULL ); - return *tape_handle(thread); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/core/test_vector.hpp b/ct_core/include/ct/external/cppad/core/test_vector.hpp deleted file mode 100644 index 5ee5d6841..000000000 --- a/ct_core/include/ct/external/cppad/core/test_vector.hpp +++ /dev/null @@ -1,136 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_TEST_VECTOR_HPP -# define CPPAD_CORE_TEST_VECTOR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin test_vector$$ -$spell - ifdef - undef - Microsofts - CppADvector - hpp - std - endif - ublas - Dir - valarray - stdvector -$$ - - -$section Choosing The Vector Testing Template Class$$ -$mindex CPPAD_TEST_VECTOR test$$ - -$head Deprecated 2012-07-03$$ -The $code CPPAD_TEST_VECTOR$$ macro has been deprecated, -use $cref/CPPAD_TESTVECTOR/testvector/$$ instead. - -$head Syntax$$ -$codei%CPPAD_TEST_VECTOR<%Scalar%> -%$$ - -$head Introduction$$ -Many of the CppAD $cref/examples/example/$$ and tests use -the $code CPPAD_TEST_VECTOR$$ template class to pass information. -The default definition for this template class is -$cref/CppAD::vector/CppAD_vector/$$. - -$head MS Windows$$ -The include path for boost is not defined in the Windows project files. -If we are using Microsofts compiler, the following code overrides the setting -of $code CPPAD_BOOSTVECTOR$$: -$srccode%cpp% */ -// The next 7 lines are C++ source code. -# ifdef _MSC_VER -# if CPPAD_BOOSTVECTOR -# undef CPPAD_BOOSTVECTOR -# define CPPAD_BOOSTVECTOR 0 -# undef CPPAD_CPPADVECTOR -# define CPPAD_CPPADVECTOR 1 -# endif -# endif -/* %$$ - -$head CppAD::vector$$ -By default $code CPPAD_CPPADVECTOR$$ is true -and $code CPPAD_TEST_VECTOR$$ is defined by the following source code -$srccode%cpp% */ -// The next 3 line are C++ source code. -# if CPPAD_CPPADVECTOR -# define CPPAD_TEST_VECTOR CppAD::vector -# endif -/* %$$ -If you specify $code --with-eigenvector$$ on the -$cref/configure/auto_tools/Configure/$$ command line, -$code CPPAD_EIGENVECTOR$$ is true. -This vector type cannot be supported by $code CPPAD_TEST_VECTOR$$ -(use $cref/CPPAD_TESTVECTOR/testvector/$$ for this support) -so $code CppAD::vector$$ is used in this case -$srccode%cpp% */ -// The next 3 line are C++ source code. -# if CPPAD_EIGENVECTOR -# define CPPAD_TEST_VECTOR CppAD::vector -# endif -/* %$$ - - -$head std::vector$$ -If you specify $code --with-stdvector$$ on the -$cref/configure/auto_tools/Configure/$$ -command line during CppAD installation, -$code CPPAD_STDVECTOR$$ is true -and $code CPPAD_TEST_VECTOR$$ is defined by the following source code -$srccode%cpp% */ -// The next 4 lines are C++ source code. -# if CPPAD_STDVECTOR -# include -# define CPPAD_TEST_VECTOR std::vector -# endif -/* %$$ -In this case CppAD will use $code std::vector$$ for its examples and tests. -Use of $code CppAD::vector$$, $code std::vector$$, -and $code std::valarray$$ with CppAD is always tested to some degree. -Specifying $code --with-stdvector$$ will increase the amount of -$code std::vector$$ testing. - -$head boost::numeric::ublas::vector$$ -If you specify a value for $icode boost_dir$$ on the configure -command line during CppAD installation, -$code CPPAD_BOOSTVECTOR$$ is true -and $code CPPAD_TEST_VECTOR$$ is defined by the following source code -$srccode%cpp% */ -// The next 4 lines are C++ source code. -# if CPPAD_BOOSTVECTOR -# include -# define CPPAD_TEST_VECTOR boost::numeric::ublas::vector -# endif -/* %$$ -In this case CppAD will use Ublas vectors for its examples and tests. -Use of $code CppAD::vector$$, $code std::vector$$, -and $code std::valarray$$ with CppAD is always tested to some degree. -Specifying $icode boost_dir$$ will increase the amount of -Ublas vector testing. - -$head CppADvector Deprecated 2007-07-28$$ -The preprocessor symbol $code CppADvector$$ is defined to -have the same value as $code CPPAD_TEST_VECTOR$$ but its use is deprecated: -$srccode%cpp% */ -# define CppADvector CPPAD_TEST_VECTOR -/* %$$ -$end ------------------------------------------------------------------------- -*/ - -# endif diff --git a/ct_core/include/ct/external/cppad/core/testvector.hpp b/ct_core/include/ct/external/cppad/core/testvector.hpp deleted file mode 100644 index 5f4edb324..000000000 --- a/ct_core/include/ct/external/cppad/core/testvector.hpp +++ /dev/null @@ -1,113 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_TESTVECTOR_HPP -# define CPPAD_CORE_TESTVECTOR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin testvector$$ -$spell - CppAD - cmake - testvector - cppad - Eigen - ifdef - hpp - std - endif - ublas -$$ - - -$section Using The CppAD Test Vector Template Class$$ -$mindex CPPAD_TESTVECTOR$$ - -$head Syntax$$ -$codei%CPPAD_TESTVECTOR(%Scalar%) -%$$ - -$head Introduction$$ -Many of the CppAD $cref/examples/example/$$ and tests use -the $code CPPAD_TESTVECTOR$$ template class to pass information to CppAD. -This is not a true template class because it's syntax uses -$codei%(%Scalar%)%$$ instead of $codei%<%Scalar%>%$$. -This enables us to use -$codei% - Eigen::Matrix<%Scalar%, Eigen::Dynamic, 1> -%$$ -as one of the possible cases for this 'template class'. - -$head CppAD::vector$$ -If in the $cref/cmake command/cmake/CMake Command/$$ -you specify $cref cppad_testvector$$ to be $code cppad$$, -$code CPPAD_CPPADVECTOR$$ will be true. -In this case, -$code CPPAD_TESTVECTOR$$ is defined by the following source code: -$srccode%cpp% */ -# if CPPAD_CPPADVECTOR -# define CPPAD_TESTVECTOR(Scalar) CppAD::vector< Scalar > -# endif -/* %$$ -In this case CppAD will use its own vector for -many of its examples and tests. - -$head std::vector$$ -If in the cmake command -you specify $icode cppad_testvector$$ to be $code std$$, -$code CPPAD_STDVECTOR$$ will be true. -In this case, -$code CPPAD_TESTVECTOR$$ is defined by the following source code: -$srccode%cpp% */ -# if CPPAD_STDVECTOR -# include -# define CPPAD_TESTVECTOR(Scalar) std::vector< Scalar > -# endif -/* %$$ -In this case CppAD will use standard vector for -many of its examples and tests. - -$head boost::numeric::ublas::vector$$ -If in the cmake command -you specify $icode cppad_testvector$$ to be $code boost$$, -$code CPPAD_BOOSTVECTOR$$ will be true. -In this case, -$code CPPAD_TESTVECTOR$$ is defined by the following source code: -$srccode%cpp% */ -# if CPPAD_BOOSTVECTOR -# include -# define CPPAD_TESTVECTOR(Scalar) boost::numeric::ublas::vector< Scalar > -# endif -/* %$$ -In this case CppAD will use this boost vector for -many of its examples and tests. - -$head Eigen Vectors$$ -If in the cmake command -you specify $icode cppad_testvector$$ to be $code eigen$$, -$code CPPAD_EIGENVECTOR$$ will be true. -In this case, -$code CPPAD_TESTVECTOR$$ is defined by the following source code: -$srccode%cpp% */ -# if CPPAD_EIGENVECTOR -# include -# define CPPAD_TESTVECTOR(Scalar) Eigen::Matrix< Scalar , Eigen::Dynamic, 1> -# endif -/* %$$ -In this case CppAD will use the Eigen vector -for many of its examples and tests. - -$end ------------------------------------------------------------------------- -*/ - -# endif diff --git a/ct_core/include/ct/external/cppad/core/unary_minus.hpp b/ct_core/include/ct/external/cppad/core/unary_minus.hpp deleted file mode 100644 index a89f5e30c..000000000 --- a/ct_core/include/ct/external/cppad/core/unary_minus.hpp +++ /dev/null @@ -1,104 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_UNARY_MINUS_HPP -# define CPPAD_CORE_UNARY_MINUS_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin UnaryMinus$$ -$spell - Vec - const - inline -$$ - - -$section AD Unary Minus Operator$$ -$mindex -$$ - -$head Syntax$$ - -$icode%y% = - %x%$$ - - -$head Purpose$$ -Computes the negative of $icode x$$. - -$head Base$$ -The operation in the syntax above must be supported for the case where -the operand is a $code const$$ $icode Base$$ object. - -$head x$$ -The operand $icode x$$ has one of the following prototypes -$codei% - const AD<%Base%> &%x% - const VecAD<%Base%>::reference &%x% -%$$ - -$head y$$ -The result $icode y$$ has type -$codei% - AD<%Base%> %y% -%$$ -It is equal to the negative of the operand $icode x$$. - -$head Operation Sequence$$ -This is an AD of $icode Base$$ -$cref/atomic operation/glossary/Operation/Atomic/$$ -and hence is part of the current -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Derivative$$ -If $latex f$$ is a -$cref/Base function/glossary/Base Function/$$, -$latex \[ - \D{[ - f(x) ]}{x} = - \D{f(x)}{x} -\] $$ - -$head Example$$ -$children% - example/unary_minus.cpp -%$$ -The file -$cref unary_minus.cpp$$ -contains an example and test of this operation. - -$end -------------------------------------------------------------------------------- -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -// Broken g++ compiler inhibits declaring unary minus a member or friend -template -inline AD AD::operator - (void) const -{ // should make a more efficient version by adding unary minus to - // Operator.h (some day) - AD result(0); - - result -= *this; - - return result; -} - - -template -inline AD operator - (const VecAD_reference &right) -{ return - right.ADBase(); } - -} -// END CppAD namespace - - -# endif diff --git a/ct_core/include/ct/external/cppad/core/unary_plus.hpp b/ct_core/include/ct/external/cppad/core/unary_plus.hpp deleted file mode 100644 index ea46568e4..000000000 --- a/ct_core/include/ct/external/cppad/core/unary_plus.hpp +++ /dev/null @@ -1,99 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_UNARY_PLUS_HPP -# define CPPAD_CORE_UNARY_PLUS_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin UnaryPlus$$ -$spell - Vec - const - inline -$$ - - -$section AD Unary Plus Operator$$ -$mindex +$$ - -$head Syntax$$ - -$icode%y% = + %x%$$ - - -$head Purpose$$ -Performs the unary plus operation -(the result $icode y$$ is equal to the operand $icode x$$). - - -$head x$$ -The operand $icode x$$ has one of the following prototypes -$codei% - const AD<%Base%> &%x% - const VecAD<%Base%>::reference &%x% -%$$ - -$head y$$ -The result $icode y$$ has type -$codei% - AD<%Base%> %y% -%$$ -It is equal to the operand $icode x$$. - -$head Operation Sequence$$ -This is an AD of $icode Base$$ -$cref/atomic operation/glossary/Operation/Atomic/$$ -and hence is part of the current -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Derivative$$ -If $latex f$$ is a -$cref/Base function/glossary/Base Function/$$, -$latex \[ - \D{[ + f(x) ]}{x} = \D{f(x)}{x} -\] $$ - - - -$head Example$$ -$children% - example/unary_plus.cpp -%$$ -The file -$cref unary_plus.cpp$$ -contains an example and test of this operation. - -$end -------------------------------------------------------------------------------- -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -inline AD AD::operator + (void) const -{ AD result(*this); - - return result; -} - - -template -inline AD operator + (const VecAD_reference &right) -{ return right.ADBase(); } - -} -// END CppAD namespace - - -# endif diff --git a/ct_core/include/ct/external/cppad/core/undef.hpp b/ct_core/include/ct/external/cppad/core/undef.hpp deleted file mode 100644 index ab640295d..000000000 --- a/ct_core/include/ct/external/cppad/core/undef.hpp +++ /dev/null @@ -1,97 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_UNDEF_HPP -# define CPPAD_CORE_UNDEF_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ----------------------------------------------------------------------------- -Preprecessor definitions that presist after cppad/cppad.hpp is included: - -# undef CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL used by CPPAD_USER_ATOMIC -# undef CPPAD_ASSERT_KNOWN used by cppad_ipopt -# undef CPPAD_ASSERT_UNKNOWN used by cppad_ipopt -# undef CPPAD_HASH_TABLE_SIZE used by test_more/optimize.cpp -# undef EIGEN_MATRIXBASE_PLUGIN example use of Eigen with CppAD -# undef CPPAD_HAS_COLPACK used by speed/cppad/sparse_*.cpp - -# undef CPPAD_BOOL_BINARY in user api -# undef CPPAD_BOOL_UNARY in user api -# undef CPPAD_DISCRETE_FUNCTION in user api -# undef CPPAD_EIGENVECTOR in user api -# undef CPPAD_MAX_NUM_THREADS in user api -# undef CPPAD_NUMERIC_LIMITS in user api -# undef CPPAD_NULL in user api -# undef CPPAD_PACKAGE_STRING in user api -# undef CPPAD_STANDARD_MATH_UNARY in user api -# undef CPPAD_TAPE_ADDR_TYPE in user api -# undef CPPAD_TAPE_ID_TYPE in user api -# undef CPPAD_TESTVECTOR in user api -# undef CPPAD_TO_STRING in user api -# undef CPPAD_USE_CPLUSPLUS_2011 in user api - -# undef CPPAD_TRACK_COUNT in deprecated api -# undef CPPAD_TRACK_DEL_VEC in deprecated api -# undef CPPAD_TRACK_EXTEND in deprecated api -# undef CPPAD_TRACK_NEW_VEC in deprecated api -# undef CPPAD_USER_ATOMIC in deprecated api - -# undef CPPAD_TEST_VECTOR deprecated verssion of CPPAD_TESTVECTOR -# undef CppADCreateBinaryBool deprecated version of CPPAD_BOOL_BINARY -# undef CppADCreateDiscrete deprecated version of CPPAD_DISCRETE_FUNCTION -# undef CppADCreateUnaryBool deprecated version of CPPAD_BOOL_UNARY -# undef CppADTrackCount deprecated version of CPPAD_TRACK_COUNT -# undef CppADTrackDelVec deprecated version of CPPAD_TRACK_DEL_VEC -# undef CppADTrackExtend deprecated version of CPPAD_TRACK_EXTEND -# undef CppADTrackNewVec deprecated version of CPPAD_TRACK_NEW_VEC -# undef CppADvector deprecated version of CPPAD_TEST_VECTOR - -// for conditional testing when implicit conversion is not present -# undef CPPAD_DEPRECATED ------------------------------------------------------------------------------ -*/ -// Preprecessor definitions that do not presist -# undef CPPAD_ASSERT_NARG_NRES -# undef CPPAD_ASSERT_ARG_BEFORE_RESULT -# undef CPPAD_AZMUL -# undef CPPAD_BOOSTVECTOR -# undef CPPAD_COND_EXP -# undef CPPAD_COND_EXP_BASE_REL -# undef CPPAD_COND_EXP_REL -# undef CPPAD_CPPADVECTOR -# undef CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR -# undef CPPAD_FOLD_ASSIGNMENT_OPERATOR -# undef CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR -# undef CPPAD_FOR_JAC_SWEEP_TRACE -# undef CPPAD_HAS_GETTIMEOFDAY -# undef CPPAD_HAS_MKSTEMP -# undef CPPAD_HAS_TMPNAM_S -# undef CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -# undef CPPAD_LIB_EXPORT -# undef CPPAD_MAX_NUM_CAPACITY -# undef CPPAD_MIN_DOUBLE_CAPACITY -# undef CPPAD_OP_CODE_TYPE -# undef CPPAD_REVERSE_SWEEP_TRACE -# undef CPPAD_REV_HES_SWEEP_TRACE -# undef CPPAD_REV_JAC_SWEEP_TRACE -# undef CPPAD_SIZE_T_NOT_UNSIGNED_INT -# undef CPPAD_STANDARD_MATH_UNARY_AD -# undef CPPAD_STDVECTOR -# undef CPPAD_TRACE_CAPACITY -# undef CPPAD_TRACE_THREAD -# undef CPPAD_TRACK_DEBUG -# undef CPPAD_USER_MACRO -# undef CPPAD_USER_MACRO_ONE -# undef CPPAD_USER_MACRO_TWO -# undef CPPAD_VEC_AD_COMPUTED_ASSIGNMENT - -# endif diff --git a/ct_core/include/ct/external/cppad/core/user_ad.hpp b/ct_core/include/ct/external/cppad/core/user_ad.hpp deleted file mode 100644 index d4306bcfb..000000000 --- a/ct_core/include/ct/external/cppad/core/user_ad.hpp +++ /dev/null @@ -1,73 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_USER_AD_HPP -# define CPPAD_CORE_USER_AD_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* ---------------------------------------------------------------------------- - -$begin AD$$ -$spell - std - bool - cos - Cpp -$$ - -$section AD Objects$$ -$mindex require$$ - - -$head Purpose$$ -The sections listed below describe the operations -that are available to $cref/AD of Base/glossary/AD of Base/$$ objects. -These objects are used to $cref/tape/glossary/Tape/$$ -an AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. -This operation sequence can -be transferred to an $cref ADFun$$ object where it -can be used to evaluate the corresponding -function and derivative values. - -$head Base Type Requirements$$ -The $icode Base$$ requirements are provided by the CppAD package -for the following base types: -$code float$$, -$code double$$, -$code std::complex$$, -$code std::complex$$. -Otherwise, see $cref base_require$$. - - -$childtable% - cppad/core/ad_ctor.hpp% - cppad/core/ad_assign.hpp% - cppad/core/convert.hpp% - cppad/core/ad_valued.hpp% - cppad/core/bool_valued.hpp% - cppad/core/vec_ad.hpp% - cppad/base_require.hpp -%$$ - -$end ---------------------------------------------------------------------------- -*/ - -# include -# include -# include -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/core/value.hpp b/ct_core/include/ct/external/cppad/core/value.hpp deleted file mode 100644 index 4535fa4fc..000000000 --- a/ct_core/include/ct/external/cppad/core/value.hpp +++ /dev/null @@ -1,101 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_VALUE_HPP -# define CPPAD_CORE_VALUE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Value$$ -$spell - const -$$ - - - -$section Convert From an AD Type to its Base Type$$ -$mindex Value$$ - -$head Syntax$$ -$icode%b% = Value(%x%)%$$ - -$head See Also$$ -$cref var2par$$ - - -$head Purpose$$ -Converts from an AD type to the corresponding -$cref/base type/glossary/Base Type/$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const AD<%Base%> &%x% -%$$ - -$head b$$ -The return value $icode b$$ has prototype -$codei% - %Base% %b% -%$$ - -$head Operation Sequence$$ -The result of this operation is not an -$cref/AD of Base/glossary/AD of Base/$$ object. -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Restriction$$ -If the argument $icode x$$ is a -$cref/variable/glossary/Variable/$$ its dependency information -would not be included in the $code Value$$ result (see above). -For this reason, -the argument $icode x$$ must be a $cref/parameter/glossary/Parameter/$$; i.e., -it cannot depend on the current -$cref/independent variables/glossary/Tape/Independent Variable/$$. - -$head Example$$ -$children% - example/value.cpp -%$$ -The file -$cref value.cpp$$ -contains an example and test of this operation. - -$end -------------------------------------------------------------------------------- -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -Base Value(const AD &x) -{ Base result; - - CPPAD_ASSERT_KNOWN( - Parameter(x) , - "Value: argument is a variable (not a parameter)" - ); - - - result = x.value_; - - return result; -} - -} -// END CppAD namespace - - -# endif diff --git a/ct_core/include/ct/external/cppad/core/var2par.hpp b/ct_core/include/ct/external/cppad/core/var2par.hpp deleted file mode 100644 index eac74dce4..000000000 --- a/ct_core/include/ct/external/cppad/core/var2par.hpp +++ /dev/null @@ -1,92 +0,0 @@ -// $Id$ -# ifndef CPPAD_CORE_VAR2PAR_HPP -# define CPPAD_CORE_VAR2PAR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ------------------------------------------------------------------------------- - -$begin Var2Par$$ -$spell - var - const -$$ - - -$section Convert an AD Variable to a Parameter$$ -$mindex Var2Par from value_ obtain during taping$$ - -$head Syntax$$ -$icode%y% = Var2Par(%x%)%$$ - -$head See Also$$ -$cref value$$ - - -$head Purpose$$ -Returns a -$cref/parameter/glossary/Parameter/$$ $icode y$$ -with the same value as the -$cref/variable/glossary/Variable/$$ $icode x$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const AD<%Base%> &x -%$$ -The argument $icode x$$ may be a variable or parameter. - - -$head y$$ -The result $icode y$$ has prototype -$codei% - AD<%Base%> &y -%$$ -The return value $icode y$$ will be a parameter. - - -$head Example$$ -$children% - example/var2par.cpp -%$$ -The file -$cref var2par.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------- -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -AD Var2Par(const AD &x) -{ AD y(x.value_); - return y; -} - - -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -AD Var2Par(const VecAD_reference &x) -{ AD y(x.ADBase()); - y.id_ = 0; -} - - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/core/vec_ad.hpp b/ct_core/include/ct/external/cppad/core/vec_ad.hpp deleted file mode 100644 index e187536f4..000000000 --- a/ct_core/include/ct/external/cppad/core/vec_ad.hpp +++ /dev/null @@ -1,741 +0,0 @@ -# ifndef CPPAD_CORE_VEC_AD_HPP -# define CPPAD_CORE_VEC_AD_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-17 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin VecAD$$ -$spell - cppad.hpp - CondExpGt - grep - Ld - vp - Lu - wc - op - Ldp - Ldv - Taylor - VecAD - const - Cpp -$$ - - -$section AD Vectors that Record Index Operations$$ -$mindex VecAD tape reference VecAD$$ - - -$head Syntax$$ -$codei%VecAD<%Base%> %v%(%n%)%$$ -$pre -$$ -$icode%v%.size()%$$ -$pre -$$ -$icode%b% = %v%[%i%]%$$ -$pre -$$ -$icode%r% = %v%[%x%]%$$ - -$head Purpose$$ -If either $icode v$$ or $icode x$$ is a -$cref/variable/glossary/Variable/$$, -the indexing operation -$codei% - %r% = %v%[%x%] -%$$ -is recorded in the corresponding -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$ and -transferred to the corresponding $cref ADFun$$ object $icode f$$. -Such an index can change each time -zero order $cref/f.Forward/Forward/$$ is used; i.e., -$icode f$$ is evaluated with new value for the -$cref/independent variables/glossary/Tape/Independent Variable/$$. -Note that the value of $icode y$$ depends on the value of $icode x$$ -in a discrete fashion and CppAD computes its partial derivative with -respect to $icode x$$ as zero. - -$head Alternatives$$ -If only the values in the vector, -and not the indices, -depend on the independent variables, -the class $icode%Vector%< AD<%Base%> >%$$ is much more efficient for -storing AD values where $icode Vector$$ is any -$cref SimpleVector$$ template class, -If only the indices, -and not the values in the vector, -depend on the independent variables, -The $cref Discrete$$ functions are a much more efficient -way to represent these vectors. - -$head VecAD::reference$$ -The result $icode r$$ has type -$codei% - VecAD<%Base%>::reference -%$$ -which is very much like the $codei%AD<%Base%>%$$ type -with some notable exceptions: - -$subhead Exceptions$$ -$list number$$ -The object $icode r$$ cannot be used with the -$cref Value$$ function to compute the corresponding $icode Base$$ value. -If $icode v$$ and $icode i$$ are not $cref/variables/glossary/Variable/$$ -$codei% - %b% = v[%i%] -%$$ -can be used to compute the corresponding $icode Base$$ value. - -$lnext -The object $icode r$$ cannot be used -with the $cref/compound assignments operators/Arithmetic/$$ -$code +=$$, -$code -=$$, -$code *=$$, or -$code /=$$. -For example, the following syntax is not valid: -$codei% - %v%[%x%] += %z%; -%$$ -no matter what the types of $icode z$$. - -$lnext -Assignment to $icode r$$ returns a $code void$$. -For example, the following syntax is not valid: -$codei% - %z% = %v%[%x%] = %u%; -%$$ -no matter what the types of $icode z$$, and $icode u$$. - -$lnext -The $cref CondExp$$ functions do not accept -$codei%VecAD<%Base%>::reference%$$ arguments. -For example, the following syntax is not valid: -$codei% - CondExpGt(%v%[%x%], %z%, %u%, %v%) -%$$ -no matter what the types of $icode z$$, $icode u$$, and $icode v$$. - -$lnext -The $cref/Parameter and Variable/ParVar/$$ functions cannot be used with -$codei%VecAD<%Base%>::reference%$$ arguments like $icode r$$, -use the entire $codei%VecAD<%Base%>%$$ vector instead; i.e. $icode v$$. - -$lnext -The vectors passed to $cref Independent$$ must have elements -of type $codei%AD<%Base%>%$$; i.e., $cref VecAD$$ vectors -cannot be passed to $code Independent$$. - -$lnext -If one uses this type in a -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$, -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ calculations -($cref Sparse$$) -are less efficient because the dependence of different -elements of the vector cannot be separated. - -$lend - -$head Constructor$$ - -$subhead v$$ -The syntax -$codei% - VecAD<%Base%> %v%(%n%) -%$$ -creates an $code VecAD$$ object $icode v$$ with -$icode n$$ elements. -The initial value of the elements of $icode v$$ is unspecified. - -$head n$$ -The argument $icode n$$ has prototype -$codei% - size_t %n% -%$$ - -$head size$$ -The syntax -$codei% - %v%.size() -%$$ -returns the number of elements in the vector $icode v$$; -i.e., the value of $icode n$$ when it was constructed. - -$head size_t Indexing$$ -We refer to the syntax -$codei% - %b% = %v%[%i%] -%$$ -as $code size_t$$ indexing of a $code VecAD$$ object. -This indexing is only valid if the vector $icode v$$ is a -$cref/parameter/ParVar/$$; i.e., -it does not depend on the independent variables. - -$subhead i$$ -The operand $icode i$$ has prototype -$codei% - size_t %i% -%$$ -It must be greater than or equal zero -and less than $icode n$$; i.e., less than -the number of elements in $icode v$$. - -$subhead b$$ -The result $icode b$$ has prototype -$codei% - %Base% %b% -%$$ -and is a reference to the $th i$$ element in the vector $icode v$$. -It can be used to change the element value; -for example, -$codei% - %v%[%i%] = %c% -%$$ -is valid where $icode c$$ is a $icode Base$$ object. -The reference $icode b$$ is no longer valid once the -destructor for $icode v$$ is called; for example, -when $icode v$$ falls out of scope. - -$head AD Indexing$$ -We refer to the syntax -$codei% - %r% = %v%[%x%] -%$$ -as AD indexing of a $code VecAD$$ object. - -$subhead x$$ -The argument $icode x$$ has prototype -$codei% - const AD<%Base%> &%x% -%$$ -The value of $icode x$$ must be greater than or equal zero -and less than $icode n$$; i.e., less than -the number of elements in $icode v$$. - -$subhead r$$ -The result $icode r$$ has prototype -$codei% - VecAD<%Base%>::reference %r% -%$$ -The object $icode r$$ has an AD type and its -operations are recorded as part of the same -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$ as -for $codei%AD<%Base%>%$$ objects. -It acts as a reference to the -element with index $latex {\rm floor} (x)$$ in the vector $icode v$$ -($latex {\rm floor} (x)$$ is -the greatest integer less than or equal $icode x$$). -Because it is a reference, it can be used to change the element value; -for example, -$codei% - %v%[%x%] = %z% -%$$ -is valid where $icode z$$ is an -$codei%VecAD<%Base%>::reference%$$ object. -As a reference, $icode r$$ is no longer valid once the -destructor for $icode v$$ is called; for example, -when $icode v$$ falls out of scope. - -$head Example$$ -$children% - example/vec_ad.cpp -%$$ -The file -$cref vec_ad.cpp$$ -contains an example and test using $code VecAD$$ vectors. -It returns true if it succeeds and false otherwise. - - -$head Speed and Memory$$ -The $cref VecAD$$ vector type is inefficient because every -time an element of a vector is accessed, a new CppAD -$cref/variable/glossary/Variable/$$ is created on the tape -using either the $code Ldp$$ or $code Ldv$$ operation -(unless all of the elements of the vector are -$cref/parameters/glossary/Parameter/$$). -The effect of this can be seen by executing the following steps: - -$list number$$ -In the file $code cppad/local/forward1sweep.h$$, -change the definition of $code CPPAD_FORWARD1SWEEP_TRACE$$ to -$codep - # define CPPAD_FORWARD1SWEEP_TRACE 1 -$$ -$lnext -In the $code Example$$ directory, execute the command -$codep - ./test_one.sh lu_vec_ad_ok.cpp lu_vec_ad.cpp -DNDEBUG > lu_vec_ad_ok.log -$$ -This will write a trace of all the forward tape operations, -for the test case $cref lu_vec_ad_ok.cpp$$, -to the file $code lu_vec_ad_ok.log$$. -$lnext -In the $code Example$$ directory execute the commands -$codep - grep "op=" lu_vec_ad_ok.log | wc -l - grep "op=Ld[vp]" lu_vec_ad_ok.log | wc -l - grep "op=St[vp][vp]" lu_vec_ad_ok.log | wc -l -$$ -The first command counts the number of operators in the tracing, -the second counts the number of VecAD load operations, -and the third counts the number of VecAD store operations. -(For CppAD version 05-11-20 these counts were 956, 348, and 118 -respectively.) -$lend - -$end ------------------------------------------------------------------------- -*/ -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file vec_ad.hpp -Defines the VecAD class. -*/ - -/*! -\def CPPAD_VEC_AD_COMPUTED_ASSIGNMENT(op, name) -Prints an error message if the correspinding compound assignment is used. - -THis macro is used to print an error message if any of the -compound assignments are used with the VecAD_reference class. -The argument \c op is one of the following: -+= , -= , *= , /=. -The argument \c name, is a string literal with the name of the -compound assignment \c op. -*/ -# define CPPAD_VEC_AD_COMPUTED_ASSIGNMENT(op, name) \ -VecAD_reference& operator op (const VecAD_reference &right) \ -{ CPPAD_ASSERT_KNOWN( \ - false, \ - "Cannot use a ADVec element on left side of" name \ - ); \ - return *this; \ -} \ -VecAD_reference& operator op (const AD &right) \ -{ CPPAD_ASSERT_KNOWN( \ - false, \ - "Cannot use a ADVec element on left side of" name \ - ); \ - return *this; \ -} \ -VecAD_reference& operator op (const Base &right) \ -{ CPPAD_ASSERT_KNOWN( \ - false, \ - "Cannot use a ADVec element on left side of" name \ - ); \ - return *this; \ -} - -/*! -Class used to hold a reference to an element of a VecAD object. - -\tparam Base -Elements of this class act like an AD (in a restricted sense), -in addition they track (on the tape) the index they correspond to. -*/ -template -class VecAD_reference { - friend bool Parameter (const VecAD &vec); - friend bool Variable (const VecAD &vec); - friend class VecAD; - friend class local::ADTape; - -private: - /// pointer to vecad vector that this is a element of - VecAD *vec_; - /// index in vecad vector that this element corresponds to - AD ind_; // index for this element -public: - /*! - consructor - - \param vec - value of vec_ - - \param ind - value of ind_ - */ - VecAD_reference(VecAD *vec, const AD& ind) - : vec_( vec ) , ind_(ind) - { } - - // assignment operators - inline void operator = (const VecAD_reference &right); - void operator = (const AD &right); - void operator = (const Base &right); - void operator = (int right); - - // compound assignments - CPPAD_VEC_AD_COMPUTED_ASSIGNMENT( += , " += " ) - CPPAD_VEC_AD_COMPUTED_ASSIGNMENT( -= , " -= " ) - CPPAD_VEC_AD_COMPUTED_ASSIGNMENT( *= , " *= " ) - CPPAD_VEC_AD_COMPUTED_ASSIGNMENT( /= , " /= " ) - - - /// Conversion from VecAD_reference to AD. - /// puts the correspond vecad load instruction in the tape. - AD ADBase(void) const - { AD result; - - size_t i = static_cast( Integer(ind_) ); - CPPAD_ASSERT_UNKNOWN( i < vec_->length_ ); - - // AD value corresponding to this element - result.value_ = vec_->data_[i]; - - // this address will be recorded in tape and must be - // zero for parameters - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - result.taddr_ = 0; - - // index corresponding to this element - if( Variable(*vec_) ) - { - local::ADTape* tape = AD::tape_ptr(vec_->tape_id_); - CPPAD_ASSERT_UNKNOWN( tape != CPPAD_NULL ); - CPPAD_ASSERT_UNKNOWN( vec_->offset_ > 0 ); - - size_t load_op_index = tape->Rec_.num_load_op_rec(); - if( IdenticalPar(ind_) ) - { CPPAD_ASSERT_UNKNOWN( local::NumRes(local::LdpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::LdpOp) == 3 ); - - // put operand addresses in tape - tape->Rec_.PutArg( - vec_->offset_, i, load_op_index - ); - // put operator in the tape, ind_ is a parameter - result.taddr_ = tape->Rec_.PutLoadOp(local::LdpOp); - // change result to variable for this load - result.tape_id_ = tape->id_; - } - else - { CPPAD_ASSERT_UNKNOWN( local::NumRes(local::LdvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( local::NumArg(local::LdvOp) == 3 ); - addr_t ind_taddr; - if( Parameter(ind_) ) - { // kludge that should not be needed - // if ind_ instead of i is used for index - // in the tape - ind_taddr = tape->RecordParOp( - ind_.value_ - ); - } - else ind_taddr = ind_.taddr_; - CPPAD_ASSERT_UNKNOWN( ind_taddr > 0 ); - - // put operand addresses in tape - // (value of third arugment does not matter) - tape->Rec_.PutArg( - vec_->offset_, ind_taddr, load_op_index - ); - // put operator in the tape, ind_ is a variable - result.taddr_ = tape->Rec_.PutLoadOp(local::LdvOp); - // change result to variable for this load - result.tape_id_ = tape->id_; - } - } - return result; - } -}; - -/*! -Vector of AD objects that tracks indexing operations on the tape. -*/ -template -class VecAD { - friend bool Parameter (const VecAD &vec); - friend bool Variable (const VecAD &vec); - friend class local::ADTape; - friend class VecAD_reference; - - friend std::ostream& operator << - (std::ostream &os, const VecAD &vec_); -private: - /// size of this VecAD vector - const size_t length_; - - /// elements of this vector - local::pod_vector data_; - - /// offset in cummulate vector corresponding to this object - size_t offset_; - - /// tape id corresponding to the offset - tape_id_t tape_id_; -public: - /// declare the user's view of this type here - typedef VecAD_reference reference; - - /// default constructor - /// initialize tape_id_ same as for default constructor; see default.hpp - VecAD(void) - : length_(0) - , offset_(0) - , tape_id_(0) - { CPPAD_ASSERT_UNKNOWN( Parameter(*this) ); } - - /// sizing constructor - /// initialize tape_id_ same as for parameters; see ad_copy.hpp - VecAD(size_t n) - : length_(n) - , offset_(0) - , tape_id_(0) - { if( length_ > 0 ) - { size_t i; - Base zero(0); - data_.extend(length_); - - // Initialize data to zero so all have same value. - // This uses less memory and avoids a valgrind error - // during TapeRec::PutPar - for(i = 0; i < length_; i++) - data_[i] = zero; - } - CPPAD_ASSERT_UNKNOWN( Parameter(*this) ); - } - - /// destructor - ~VecAD(void) - { } - - /// number of elements in the vector - size_t size(void) - { return length_; } - - /// element access (not taped) - /// - /// \param i - /// element index - Base &operator[](size_t i) - { - CPPAD_ASSERT_KNOWN( - Parameter(*this), - "VecAD: cannot use size_t indexing because this" - " VecAD vector is a variable." - ); - CPPAD_ASSERT_KNOWN( - i < length_, - "VecAD: element index is >= vector length" - ); - - return data_[i]; - } - - /*! delayed taped elemement access - - \param x - element index - - \par - This operation may convert this vector from a parameter to a variable - */ - VecAD_reference operator[](const AD &x) - { - CPPAD_ASSERT_KNOWN( - 0 <= Integer(x), - "VecAD: element index is less than zero" - ); - CPPAD_ASSERT_KNOWN( - static_cast( Integer(x) ) < length_, - "VecAD: element index is >= vector length" - ); - - // if no need to track indexing operation, return now - if( Parameter(*this) & Parameter(x) ) - return VecAD_reference(this, x); - - CPPAD_ASSERT_KNOWN( - Parameter(*this) | Parameter(x) | (tape_id_ == x.tape_id_), - "VecAD: vector and index are variables for" - " different tapes." - ); - - if( Parameter(*this) ) - { // must place a copy of vector in tape - offset_ = - AD::tape_ptr(x.tape_id_)->AddVec(length_, data_); - - // Advance pointer by one so starts at first component of this - // vector; i.e., skip lenght at begining (so is always > 0) - offset_++; - - // tape id corresponding to this offest - tape_id_ = x.tape_id_; - } - - return VecAD_reference(this, x); - } - -}; - - -/*! -Taped setting of element to a value. - -\param y -value that element is set to. -*/ -template -void VecAD_reference::operator=(const AD &y) -{ - if( Parameter(y) ) - { // fold into the Base type assignment - *this = y.value_; - return; - } - CPPAD_ASSERT_UNKNOWN( y.taddr_ > 0 ); - - CPPAD_ASSERT_KNOWN( - Parameter(*vec_) | (vec_->tape_id_ == y.tape_id_), - "VecAD assignment: vector and new element value are variables" - "\nfor different tapes." - ); - - local::ADTape* tape = AD::tape_ptr(y.tape_id_); - CPPAD_ASSERT_UNKNOWN( tape != CPPAD_NULL ); - if( Parameter(*vec_) ) - { // must place a copy of vector in tape - vec_->offset_ = tape->AddVec(vec_->length_, vec_->data_); - - // advance offset to be start of vector plus one - (vec_->offset_)++; - - // tape id corresponding to this offest - vec_->tape_id_ = y.tape_id_; - } - CPPAD_ASSERT_UNKNOWN( Variable(*vec_) ); - - - // index in vector for this element - size_t i = static_cast( Integer(ind_) ); - CPPAD_ASSERT_UNKNOWN( i < vec_->length_ ); - - // assign value for this element (as an AD object) - vec_->data_[i] = y.value_; - - // record the setting of this array element - CPPAD_ASSERT_UNKNOWN( vec_->offset_ > 0 ); - if( Parameter(ind_) ) - { CPPAD_ASSERT_UNKNOWN( local::NumArg(local::StpvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::StpvOp) == 0 ); - - // put operand addresses in tape - tape->Rec_.PutArg(vec_->offset_, i, y.taddr_); - - // put operator in the tape, ind_ is parameter, y is variable - tape->Rec_.PutOp(local::StpvOp); - } - else - { CPPAD_ASSERT_UNKNOWN( local::NumArg(local::StvvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::StvvOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( ind_.taddr_ > 0 ); - - // put operand addresses in tape - tape->Rec_.PutArg(vec_->offset_, ind_.taddr_, y.taddr_); - - // put operator in the tape, ind_ is variable, y is variable - tape->Rec_.PutOp(local::StvvOp); - } -} - - -/*! -Taped setting of element to a value. - -\param y -value that element is set to. -*/ -template -void VecAD_reference::operator=(const Base &y) -{ - size_t i = static_cast( Integer(ind_) ); - CPPAD_ASSERT_UNKNOWN( i < vec_->length_ ); - - // assign value for this element - vec_->data_[i] = y; - - // check if this ADVec object is a parameter - if( Parameter(*vec_) ) - return; - - local::ADTape* tape = AD::tape_ptr(vec_->tape_id_); - CPPAD_ASSERT_UNKNOWN( tape != CPPAD_NULL ); - - // put value of the parameter y in the tape - addr_t p = tape->Rec_.PutPar(y); - - // record the setting of this array element - CPPAD_ASSERT_UNKNOWN( vec_->offset_ > 0 ); - if( Parameter(ind_) ) - { CPPAD_ASSERT_UNKNOWN( local::NumArg(local::StppOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::StppOp) == 0 ); - - // put operand addresses in tape - tape->Rec_.PutArg(vec_->offset_, i, p); - - // put operator in the tape, ind_ is parameter, y is parameter - tape->Rec_.PutOp(local::StppOp); - } - else - { CPPAD_ASSERT_UNKNOWN( local::NumArg(local::StvpOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( local::NumRes(local::StvpOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( ind_.taddr_ > 0 ); - - // put operand addresses in tape - tape->Rec_.PutArg(vec_->offset_, ind_.taddr_, p); - - // put operator in the tape, ind_ is variable, y is parameter - tape->Rec_.PutOp(local::StvpOp); - } -} - -/*! -Taped setting of element to a value. - -\param y -value that element is set to. - -\par -this case gets folded into case where value is AD. -*/ -template -inline void VecAD_reference::operator= -(const VecAD_reference &y) -{ *this = y.ADBase(); } - -/*! -Taped setting of element to a value. - -\param y -value that element is set to. - -\par -this case gets folded into case where value is Base. -*/ -template -inline void VecAD_reference::operator=(int y) -{ *this = Base(y); } - - -} // END_CPPAD_NAMESPACE - -// preprocessor symbols that are local to this file -# undef CPPAD_VEC_AD_COMPUTED_ASSIGNMENT - -# endif diff --git a/ct_core/include/ct/external/cppad/core/zdouble.hpp b/ct_core/include/ct/external/cppad/core/zdouble.hpp deleted file mode 100644 index 6536cf904..000000000 --- a/ct_core/include/ct/external/cppad/core/zdouble.hpp +++ /dev/null @@ -1,548 +0,0 @@ -# ifndef CPPAD_CORE_ZDOUBLE_HPP -# define CPPAD_CORE_ZDOUBLE_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-17 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin zdouble$$ -$spell - zdouble - op - bool - inf - CppAD -$$ -$section zdouble: An AD Base Type With Absolute Zero$$ - -$head Deprecated 2015-09-26$$ -Use the function $cref azmul$$ instead. - -$head Absolute Zero$$ -The $code zdouble$$ class acts like the $code double$$ type -with the added property that zero times any value is zero. -This includes zero time $cref nan$$ and zero times infinity. -In addition, zero divided by any value and any value times zero -are also zero. - -$head Syntax$$ - -$subhead Constructor and Assignment$$ -$codei% zdouble z -%$$ -$codei% zdouble z(x) -%$$ -$icode% z1% %op% %x% -%$$ -where $icode x$$ is a $code double$$ or $code zdouble$$ object -and $icode op$$ is $code =$$, $code +=$$, $code -=$$, $code *=$$ -or $code /=-$$. - -$subhead Comparison Operators$$ -$icode% b% = %z% %op% %x% -%$$ -$icode% b% = %x% %op% %z% -%$$ -where $icode b$$ is a $code bool$$ object, -$icode z$$ is a $code zdouble$$ object, -$icode x$$ is a $code double$$ or $code zdouble$$ object, and -$icode op$$ is $code ==$$, $code !=$$, $code <=$$, $code >=$$, -$code <$$ or $code >$$. - -$subhead Arithmetic Operators$$ -$icode% z2% = %z1% %op% %x% -%$$ -$icode% z2% = %x% %op% %z1% -%$$ -where $icode z1$$, $icode z2$$ are $code zdouble$$ objects, -$icode x$$ is a $code double$$ or $code zdouble$$ object, and -$icode op$$ is $code +$$, $code -$$, $code *$$ or $code /$$. - - -$subhead Standard Math$$ -$icode% z2% = %fun%(%z1%) -%$$ -$icode% z3% = pow(%z1%, %z2%) -%$$ -where $icode z1$$, $icode z2$$, $icode z3$$ are $code zdouble$$ objects and -$icode fun$$ is a $cref unary_standard_math$$ function. - -$subhead Nan$$ -There is a specialization of $cref nan$$ so that -$icode% - z2% = nan(%z1%) -%$$ -returns 'not a number' when $icode z1$$ has type $code zdouble$$. -Note that this template function needs to be specialized because -$codei - zdouble(0.0) == zdouble(0.0) / zdouble(0.0) -$$ - - -$head Motivation$$ - -$subhead General$$ -Often during computing (and more so in parallel computing) alternative -values for an expression are computed and one of the alternatives -is chosen using some boolean variable. -This is often represented by -$codei% - %result% = %flag% * %value_if_true% + (1 - %flag%) * %value_if_false% -%$$ -where $icode flag$$ is one for true and zero for false. -This representation does not work for $code double$$ when the value -being multiplied by zero is $code +inf$$, $code -inf$$, or $code nan$$. - -$subhead CppAD$$ -In CppAD one can use -$cref/conditional expressions/CondExp/$$ to achieve the representation -$codei% - %result% = %flag% * %value_if_true% + (1 - %flag%) * %value_if_false% -%$$ -This works fine except when there are -$cref/multiple levels of AD/mul_level/$$; e.g., -when using $codei%AD< AD >%$$. -In this case the corresponding AD function objects have type -$cref/ADFun< AD >/FunConstruct/$$. -When these AD function objects compute derivatives using -$cref reverse$$ mode, the conditional expressions are represented use -zeros to multiply the expression that is not used. -Using $codei%AD< AD >%$$ instead of $code AD< AD >$$ -makes this representation work and fixes the problem. - -$head Base Type Requirements$$ -The type $code zdouble$$ satisfies all of the CppAD -$cref/base type requirements/base_require/$$. - -$children% - test_more/zdouble.cpp -%$$ -$head Example$$ -The file $cref zdouble.cpp$$ -contains an example and test of this class. -It returns true if it succeeds and false otherwise. - -$end -*/ -# include -# include - -/*! -\file zdouble.hpp -Define a class like double but with an absolute zero. -*/ - -/*! -\def CPPAD_ZDOUBLE_NORMAL_ASSIGN_OPERATOR(op) -Define a compound assignment member operator that functions the same -as corresponding double operator. -*/ -# define CPPAD_ZDOUBLE_NORMAL_ASSIGN_OPERATOR(op) \ - zdouble& operator op (const zdouble& z) \ - { dbl_ op z.dbl_; \ - return *this; \ - } \ - zdouble& operator op (const double& x) \ - { dbl_ op x; \ - return *this; \ - } - -/*! -\def CPPAD_ZDOUBLE_UNARY_OPERATOR(op) -Define a unary compound assignment member operator. -*/ -# define CPPAD_ZDOUBLE_UNARY_OPERATOR(op) \ - zdouble operator op (void) const \ - { return zdouble( op dbl_ ); } - -/*! -# define CPPAD_ZDOUBLE_NORMAL_BINARY_OPERATOR(op) -Define a binary arithmetic member operator that functions the same -as corresponding double operator. -*/ -# define CPPAD_ZDOUBLE_NORMAL_BINARY_OPERATOR(op) \ - zdouble operator op (const zdouble& z) const \ - { return zdouble( dbl_ op z.dbl_ ); } \ - zdouble operator op (const double& x) const \ - { return zdouble( dbl_ op x ); } - -/*! -\def CPPAD_ZDOUBLE_COMPARE_OPERATOR(op) -Define a comparison member operator. -*/ -# define CPPAD_ZDOUBLE_COMPARE_OPERATOR(op) \ - bool operator op (const zdouble& z) const \ - { return dbl_ op z.dbl_; } \ - bool operator op (const double& x) const \ - { return dbl_ op x; } - -/*! -\def CPPAD_ZDOUBLE_OTHER_BINARY_OPERATOR(op) -Define a binary arithmetic operator that is not a member because -the double operand is on the left. -*/ -# define CPPAD_ZDOUBLE_OTHER_BINARY_OPERATOR(op) \ - inline zdouble operator op(const double& x, const zdouble& z) \ - { return zdouble(x) op z; } - -/*! -\def CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(op, op_switch) -Define a comparison operator that is not a member because -the double operand is on the left. -Convert it to the case where the double operand is on the right by -by using op_switch instead of op. -*/ -# define CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(op, op_switch) \ - inline bool operator op(const double& x, const zdouble& z) \ - { return z op_switch x; } - -/*! -\def CPPAD_ZDOUBLE_STD_MATH_FRIEND(fun) -Declare that a standard math function is a friend. -*/ -# define CPPAD_ZDOUBLE_STD_MATH_FRIEND(fun) \ - friend zdouble fun(const zdouble& z); -/*! -\def CPPAD_ZDOUBLE_STD_MATH(fun) -Define a standard math function. -*/ -# define CPPAD_ZDOUBLE_STD_MATH(fun) \ - inline zdouble fun(const zdouble& z ) \ - { return zdouble( std::fun(z.dbl_) ); } - -namespace CppAD { // CPPAD_BEGIN_NAMESPACDE - - -/*! -Class that is like double, except that it has an absolute zero. -*/ -class zdouble { - /*! - For zdouble objects z1, z2, and std::ostream os, - declare the following friends: - \code - os << z1 - Integer(z1) - fabs(z1) - pow(z1, z2) - fabs_geq(z1, z2) - fun(z1) - \endcode - where fun is any of the standard math unary functions. - */ - friend std::ostream& operator << (std::ostream &os, const zdouble& z); - friend int Integer(const zdouble& z); - friend zdouble pow(const zdouble& x, const zdouble& y); - friend bool abs_geq(const zdouble& x, const zdouble& y); - // - CPPAD_ZDOUBLE_STD_MATH_FRIEND(acos) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(asin) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(atan) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(cos) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(cosh) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(exp) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(fabs) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(log) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(log10) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(sin) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(sinh) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(sqrt) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(tan) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(tanh) - // -# if CPPAD_USE_CPLUSPLUS_2011 - CPPAD_ZDOUBLE_STD_MATH_FRIEND(erf) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(asinh) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(acosh) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(atanh) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(expm1) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(log1p) - // -# endif -private: - /// The value for this object - double dbl_; -public: - /// Default constructor - zdouble(void) - : dbl_() - { } - /// Copy constructor - zdouble(const zdouble& z) - : dbl_(z.dbl_) - { } - /// Constructor from double - zdouble(const double& dbl) - : dbl_(dbl) - { } - // - /// Destructor - ~zdouble(void) - { } - // - /// Assignment from zdouble - zdouble& operator=(const zdouble& z) - { dbl_ = z.dbl_; - return *this; - } - /// Assignment from double - zdouble& operator=(const double& dbl) - { dbl_ = dbl; - return *this; - } - // - /// Normal compound assignment - CPPAD_ZDOUBLE_NORMAL_ASSIGN_OPERATOR(+=) - /// Normal compound assignment - CPPAD_ZDOUBLE_NORMAL_ASSIGN_OPERATOR(-=) - /// Normal unary operator - CPPAD_ZDOUBLE_UNARY_OPERATOR(+) - /// Normal unary operator - CPPAD_ZDOUBLE_UNARY_OPERATOR(-) - /// Normal compare operator - CPPAD_ZDOUBLE_COMPARE_OPERATOR(==) - /// Normal compare operator - CPPAD_ZDOUBLE_COMPARE_OPERATOR(!=) - /// Normal compare operator - CPPAD_ZDOUBLE_COMPARE_OPERATOR(<=) - /// Normal compare operator - CPPAD_ZDOUBLE_COMPARE_OPERATOR(>=) - /// Normal compare operator - CPPAD_ZDOUBLE_COMPARE_OPERATOR(<) - /// Normal compare operator - CPPAD_ZDOUBLE_COMPARE_OPERATOR(>) - // - /// Normal binary arithmetic operator - CPPAD_ZDOUBLE_NORMAL_BINARY_OPERATOR(+) - /// Normal binary arithmetic operator - CPPAD_ZDOUBLE_NORMAL_BINARY_OPERATOR(-) - // - /// Binary arithmetic * with absolute zero - zdouble operator * (const zdouble& z) const - { bool zero = (dbl_ == 0.0) || (z.dbl_ == 0.0); - return zdouble( zero ? 0.0 : (dbl_ * z.dbl_) ); - } - /// Binary arithmetic * with absolute zero - zdouble operator * (const double& x) const - { bool zero = (dbl_ == 0.0) || (x == 0.0); - return zdouble( zero ? 0.0 : (dbl_ * x) ); - } - /// Binary arithmetic / with absolute zero - zdouble operator / (const zdouble& z) const - { bool zero = (dbl_ == 0.0); - return zdouble( zero ? 0.0 : (dbl_ / z.dbl_) ); - } - /// Binary arithmetic / with absolute zero - zdouble operator / (const double& x) const - { bool zero = (dbl_ == 0.0); - return zdouble( zero ? 0.0 : (dbl_ / x) ); - } - // - /// Compute assignmnet *= with absolute zero - zdouble& operator *= (const zdouble& z) - { bool zero = (dbl_ == 0.0) || (z.dbl_ == 0.0); - zero ? (dbl_ = 0.0) : (dbl_ *= z.dbl_); - return *this; - } - /// Compute assignmnet *= with absolute zero - zdouble& operator *= (const double& x) - { bool zero = (dbl_ == 0.0) || (x == 0.0); - zero ? (dbl_ = 0.0) : (dbl_ *= x); - return *this; - } - // - /// Compute assignmnet /= with absolute zero - zdouble& operator /= (const zdouble& z) - { bool zero = (dbl_ == 0.0); - zero ? (dbl_ = 0.0) : (dbl_ /= z.dbl_); - return *this; - } - /// Compute assignmnet /= with absolute zero - zdouble& operator /= (const double& x) - { bool zero = (dbl_ == 0.0); - zero ? (dbl_ = 0.0) : (dbl_ /= x); - return *this; - } -}; -// BEGIN nan -/// Must specialize CppAD::nan because zdouble 0/0 is not nan. -template <> -inline zdouble nan(const zdouble& zero) -{ - return zdouble( std::numeric_limits::quiet_NaN() ); -} -// END nan -// -/// Normal non-member compare operator -CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(==, ==) -/// Normal non-member compare operator -CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(!=, !=) -/// Normal non-member compare operator -CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(<=, >=) -/// Normal non-member compare operator -CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(>=, <=) -/// Normal non-member compare operator -CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(<, >) -/// Normal non-member compare operator -CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(>, <) -// -/// Normal binary arithmetic operator -CPPAD_ZDOUBLE_OTHER_BINARY_OPERATOR(+) -/// Normal binary arithmetic operator -CPPAD_ZDOUBLE_OTHER_BINARY_OPERATOR(-) -/// Binary arithmetic operator with absolute zero -CPPAD_ZDOUBLE_OTHER_BINARY_OPERATOR(*) -/// Binary arithmetic operator with absolute zero -CPPAD_ZDOUBLE_OTHER_BINARY_OPERATOR(/) -// ------------------------------------------------------------------------- -// Base type requirements -// ------------------------------------------------------------------------- - -/// Base type requirement: CondExpOp -inline zdouble CondExpOp( - enum CompareOp cop , - const zdouble& left , - const zdouble& right , - const zdouble& exp_if_true , - const zdouble& exp_if_false ) -{ return CondExpTemplate(cop, left, right, exp_if_true, exp_if_false); -} - -/// Base type requirement: CondExpRel -CPPAD_COND_EXP_REL(zdouble) - -/// Base type requirement: EqualOpSeq -inline bool EqualOpSeq(const zdouble& x, const zdouble& y) -{ return x == y; } - -/// Base type requirement: Identical -inline bool IdenticalPar(const zdouble& x) -{ return true; } -inline bool IdenticalZero(const zdouble& x) -{ return (x == 0.0); } -inline bool IdenticalOne(const zdouble& x) -{ return (x == 1.); } -inline bool IdenticalEqualPar(const zdouble& x, const zdouble& y) -{ return (x == y); } - -/// Base type requirement: output operator -inline std::ostream& operator << (std::ostream &os, const zdouble& z) -{ os << z.dbl_; - return os; -} - -/// Base type requirement: Integer -inline int Integer(const zdouble& x) -{ return static_cast(x.dbl_); } - -/// Base type requirement: azmul -inline zdouble azmul(const zdouble& x, const zdouble& y) -{ return x * y; } - -/// Base type requirement: Ordered -inline bool GreaterThanZero(const zdouble& x) -{ return x > 0.0; } -inline bool GreaterThanOrZero(const zdouble& x) -{ return x >= 0.0; } -inline bool LessThanZero(const zdouble& x) -{ return x < 0.0; } -inline bool LessThanOrZero(const zdouble& x) -{ return x <= 0.0; } -inline bool abs_geq(const zdouble& x, const zdouble& y) -{ return std::fabs(x.dbl_) >= std::fabs(y.dbl_); } - -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(acos) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(asin) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(atan) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(cos) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(cosh) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(exp) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(fabs) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(log) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(log10) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(sin) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(sinh) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(sqrt) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(tan) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(tanh) -// -# if CPPAD_USE_CPLUSPLUS_2011 -/// C++2011 standard math function -CPPAD_ZDOUBLE_STD_MATH(erf) -/// C++2011 standard math function -CPPAD_ZDOUBLE_STD_MATH(asinh) -/// C++2011 standard math function -CPPAD_ZDOUBLE_STD_MATH(acosh) -/// C++2011 standard math function -CPPAD_ZDOUBLE_STD_MATH(atanh) -/// C++2011 standard math function -CPPAD_ZDOUBLE_STD_MATH(expm1) -/// C++2011 standard math function -CPPAD_ZDOUBLE_STD_MATH(log1p) -# endif - -/// Base type requirement: abs -inline zdouble abs(const zdouble& x) -{ return fabs(x); } - -/// Base type requirement: sign -inline zdouble sign(const zdouble& x) -{ if( x > 0.0 ) - return zdouble(1.); - if( x == 0.0 ) - return zdouble(0.0); - return zdouble(-1.); -} - -/// Base type requirement: pow -inline zdouble pow(const zdouble& x, const zdouble& y) -{ return std::pow(x.dbl_, y.dbl_); } - -/// Base type requirement: limits -template <> -class numeric_limits { -public: - // machine epsilon - static zdouble epsilon(void) - { return std::numeric_limits::epsilon(); } - // minimum positive normalized value - static zdouble min(void) - { return std::numeric_limits::min(); } - // maximum finite value - static zdouble max(void) - { return std::numeric_limits::max(); } -}; - -} // CPPAD_END_NAMESPACE - -/// undef all macros defined in this file -# undef CPPAD_ZDOUBLE_NORMAL_ASSIGN_OPERATOR -# undef CPPAD_ZDOUBLE_UNARY_OPERATOR -# undef CPPAD_ZDOUBLE_NORMAL_BINARY_OPERATOR -# undef CPPAD_ZDOUBLE_COMPARE_OPERATOR -# undef CPPAD_ZDOUBLE_OTHER_BINARY_OPERATOR -# undef CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR -# undef CPPAD_ZDOUBLE_STD_MATH_FRIEND -# undef CPPAD_ZDOUBLE_STD_MATH - -# endif diff --git a/ct_core/include/ct/external/cppad/cppad.hpp b/ct_core/include/ct/external/cppad/cppad.hpp deleted file mode 100644 index d9f6734e4..000000000 --- a/ct_core/include/ct/external/cppad/cppad.hpp +++ /dev/null @@ -1,74 +0,0 @@ -// $Id: cppad.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_CPPAD_HPP -# define CPPAD_CPPAD_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/*! -\file cppad.hpp -\brief includes the entire CppAD package in the necessary order. - -\namespace CppAD -\brief contains all the variables and functions defined by the CppAD package. -*/ - -# include // all base type requirements -// --------------------------------------------------------------------------- -// CppAD general purpose library routines (can be included separately) -# include -// -------------------------------------------------------------------------- -// System routines that can be used by rest of CppAD with out including - -# include -# include -# include -# include - -// --------------------------------------------------------------------------- -// definitions needed by rest of includes - -// definitions that come from the installation -# include - -// definitions that are local to the CppAD include files -# include - -// vectors used with CppAD -# include - -// deprecated vectors used with CppAD -# include - -// Declare classes and fucntions that are used before defined -# include - -// --------------------------------------------------------------------------- -// declare the AD template class - -# include - -// --------------------------------------------------------------------------- - -# include // AD class methods available to the user -// tape that tape for AD acts as a user of Base operations -// so user_ad.hpp must come before op.hpp -# include // executes taped operations -# include // ADFun objects - -// --------------------------------------------------------------------------- -// library routines that require the rest of CppAD -# include -# include -# include - -// undo definitions in Define.h -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/deprecated/check_numeric_type.hpp b/ct_core/include/ct/external/cppad/deprecated/check_numeric_type.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/check_numeric_type.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/check_simple_vector.hpp b/ct_core/include/ct/external/cppad/deprecated/check_simple_vector.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/check_simple_vector.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/elapsed_seconds.hpp b/ct_core/include/ct/external/cppad/deprecated/elapsed_seconds.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/elapsed_seconds.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/error_handler.hpp b/ct_core/include/ct/external/cppad/deprecated/error_handler.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/error_handler.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/index_sort.hpp b/ct_core/include/ct/external/cppad/deprecated/index_sort.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/index_sort.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/lu_factor.hpp b/ct_core/include/ct/external/cppad/deprecated/lu_factor.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/lu_factor.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/lu_invert.hpp b/ct_core/include/ct/external/cppad/deprecated/lu_invert.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/lu_invert.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/lu_solve.hpp b/ct_core/include/ct/external/cppad/deprecated/lu_solve.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/lu_solve.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/memory_leak.hpp b/ct_core/include/ct/external/cppad/deprecated/memory_leak.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/memory_leak.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/nan.hpp b/ct_core/include/ct/external/cppad/deprecated/nan.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/nan.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/near_equal.hpp b/ct_core/include/ct/external/cppad/deprecated/near_equal.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/near_equal.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/ode_err_control.hpp b/ct_core/include/ct/external/cppad/deprecated/ode_err_control.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/ode_err_control.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/ode_gear.hpp b/ct_core/include/ct/external/cppad/deprecated/ode_gear.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/ode_gear.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/ode_gear_control.hpp b/ct_core/include/ct/external/cppad/deprecated/ode_gear_control.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/ode_gear_control.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/omp_alloc.hpp b/ct_core/include/ct/external/cppad/deprecated/omp_alloc.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/omp_alloc.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/poly.hpp b/ct_core/include/ct/external/cppad/deprecated/poly.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/poly.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/pow_int.hpp b/ct_core/include/ct/external/cppad/deprecated/pow_int.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/pow_int.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/romberg_mul.hpp b/ct_core/include/ct/external/cppad/deprecated/romberg_mul.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/romberg_mul.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/romberg_one.hpp b/ct_core/include/ct/external/cppad/deprecated/romberg_one.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/romberg_one.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/rosen_34.hpp b/ct_core/include/ct/external/cppad/deprecated/rosen_34.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/rosen_34.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/runge_45.hpp b/ct_core/include/ct/external/cppad/deprecated/runge_45.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/runge_45.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/speed_test.hpp b/ct_core/include/ct/external/cppad/deprecated/speed_test.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/speed_test.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/thread_alloc.hpp b/ct_core/include/ct/external/cppad/deprecated/thread_alloc.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/thread_alloc.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/time_test.hpp b/ct_core/include/ct/external/cppad/deprecated/time_test.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/time_test.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/track_new_del.hpp b/ct_core/include/ct/external/cppad/deprecated/track_new_del.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/track_new_del.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/deprecated/vector.hpp b/ct_core/include/ct/external/cppad/deprecated/vector.hpp deleted file mode 100644 index 285bb954a..000000000 --- a/ct_core/include/ct/external/cppad/deprecated/vector.hpp +++ /dev/null @@ -1 +0,0 @@ -# include diff --git a/ct_core/include/ct/external/cppad/example/base_adolc.hpp b/ct_core/include/ct/external/cppad/example/base_adolc.hpp deleted file mode 100644 index 2c9dc0072..000000000 --- a/ct_core/include/ct/external/cppad/example/base_adolc.hpp +++ /dev/null @@ -1,310 +0,0 @@ -// $Id: base_adolc.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_BASE_ADOLC_HPP -# define CPPAD_BASE_ADOLC_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin base_adolc.hpp$$ -$spell - azmul - expm1 - atanh - acosh - asinh - erf - ifndef - define - endif - Rel - codassign - eps - std - abs_geq - fabs - cppad.hpp - undef - Lt - Le - Eq - Ge - Gt - namespace - cassert - condassign - hpp - bool - const - Adolc - adouble - CondExpOp - inline - enum - CppAD - pow - acos - asin - atan - cos - cosh - exp - sqrt -$$ - - -$section Enable use of AD where Base is Adolc's adouble Type$$ - -$head Syntax$$ -$codei%# include -%$$ -$children% - example/mul_level_adolc.cpp -%$$ - -$head Example$$ -The file $cref mul_level_adolc.cpp$$ contains an example use of -Adolc's $code adouble$$ type for a CppAD $icode Base$$ type. -It returns true if it succeeds and false otherwise. -The file $cref mul_level_adolc_ode.cpp$$ contains a more realistic -(and complex) example. - -$head Include Files$$ -This file $code base_adolc.hpp$$ requires $code adouble$$ to be defined. -In addition, it is included before $code $$, -but it needs to include parts of CppAD that are used by this file. -This is done with the following include commands: -$codep */ -# include -# include -/* $$ - -$head CondExpOp$$ -The type $code adouble$$ supports a conditional assignment function -with the syntax -$codei% - condassign(%a%, %b%, %c%, %d%) -%$$ -which evaluates to -$codei% - %a% = (%b% > 0) ? %c% : %d%; -%$$ -This enables one to include conditionals in the recording of -$code adouble$$ operations and later evaluation for different -values of the independent variables -(in the same spirit as the CppAD $cref CondExp$$ function). -$codep */ -namespace CppAD { - inline adouble CondExpOp( - enum CppAD::CompareOp cop , - const adouble &left , - const adouble &right , - const adouble &trueCase , - const adouble &falseCase ) - { adouble result; - switch( cop ) - { - case CompareLt: // left < right - condassign(result, right - left, trueCase, falseCase); - break; - - case CompareLe: // left <= right - condassign(result, left - right, falseCase, trueCase); - break; - - case CompareEq: // left == right - condassign(result, left - right, falseCase, trueCase); - condassign(result, right - left, falseCase, result); - break; - - case CompareGe: // left >= right - condassign(result, right - left, falseCase, trueCase); - break; - - case CompareGt: // left > right - condassign(result, left - right, trueCase, falseCase); - break; - default: - CppAD::ErrorHandler::Call( - true , __LINE__ , __FILE__ , - "CppAD::CondExp", - "Error: for unknown reason." - ); - result = trueCase; - } - return result; - } -} -/* $$ - -$head CondExpRel$$ -The $cref/CPPAD_COND_EXP_REL/base_cond_exp/CondExpRel/$$ macro invocation -$codep */ -namespace CppAD { - CPPAD_COND_EXP_REL(adouble) -} -/* $$ - -$head EqualOpSeq$$ -The Adolc user interface does not specify a way to determine if -two $code adouble$$ variables correspond to the same operations sequence. -Make $code EqualOpSeq$$ an error if it gets used: -$codep */ -namespace CppAD { - inline bool EqualOpSeq(const adouble &x, const adouble &y) - { CppAD::ErrorHandler::Call( - true , __LINE__ , __FILE__ , - "CppAD::EqualOpSeq(x, y)", - "Error: adouble does not support EqualOpSeq." - ); - return false; - } -} -/* $$ - -$head Identical$$ -The Adolc user interface does not specify a way to determine if an -$code adouble$$ depends on the independent variables. -To be safe (but slow) return $code false$$ in all the cases below. -$codep */ -namespace CppAD { - inline bool IdenticalPar(const adouble &x) - { return false; } - inline bool IdenticalZero(const adouble &x) - { return false; } - inline bool IdenticalOne(const adouble &x) - { return false; } - inline bool IdenticalEqualPar(const adouble &x, const adouble &y) - { return false; } -} -/* $$ - -$head Integer$$ -$codep */ - inline int Integer(const adouble &x) - { return static_cast( x.getValue() ); } -/* $$ - -$head azmul$$ -$codep */ -namespace CppAD { - CPPAD_AZMUL( adouble ) -} -/* $$ - -$head Ordered$$ -$codep */ -namespace CppAD { - inline bool GreaterThanZero(const adouble &x) - { return (x > 0); } - inline bool GreaterThanOrZero(const adouble &x) - { return (x >= 0); } - inline bool LessThanZero(const adouble &x) - { return (x < 0); } - inline bool LessThanOrZero(const adouble &x) - { return (x <= 0); } - inline bool abs_geq(const adouble& x, const adouble& y) - { return fabs(x) >= fabs(y); } -} -/* $$ - -$head Unary Standard Math$$ -The following $cref/required/base_require/$$ functions -are defined by the Adolc package for the $code adouble$$ base case: -$pre -$$ -$code acos$$, -$code asin$$, -$code atan$$, -$code cos$$, -$code cosh$$, -$code exp$$, -$code fabs$$, -$code log$$, -$code sin$$, -$code sinh$$, -$code sqrt$$, -$code tan$$. - -$head erf, asinh, acosh, atanh, expm1, log1p$$ -If the -$cref/erf, asinh, acosh, atanh, expm1, log1p - /base_std_math - /erf, asinh, acosh, atanh, expm1, log1p -/$$, -functions are supported by the compiler, -they must also be supported by a $icode Base$$ type; -The adolc package does not support these functions so make -their use an error: -$codep */ -namespace CppAD { -# define CPPAD_BASE_ADOLC_NO_SUPPORT(fun) \ - inline adouble fun(const adouble& x) \ - { CPPAD_ASSERT_KNOWN( \ - false, \ - #fun ": adolc does not support this function" \ - ); \ - return 0.0; \ - } -# if CPPAD_USE_CPLUSPLUS_2011 - CPPAD_BASE_ADOLC_NO_SUPPORT(erf) - CPPAD_BASE_ADOLC_NO_SUPPORT(asinh) - CPPAD_BASE_ADOLC_NO_SUPPORT(acosh) - CPPAD_BASE_ADOLC_NO_SUPPORT(atanh) - CPPAD_BASE_ADOLC_NO_SUPPORT(expm1) - CPPAD_BASE_ADOLC_NO_SUPPORT(log1p) -# endif -# undef CPPAD_BASE_ADOLC_NO_SUPPORT -} -/* $$ - -$head sign$$ -This $cref/required/base_require/$$ function is defined using the -$code codassign$$ function so that its $code adouble$$ operation sequence -does not depend on the value of $icode x$$. -$codep */ -namespace CppAD { - inline adouble sign(const adouble& x) - { adouble s_plus, s_minus, half(.5); - // set s_plus to sign(x)/2, except for case x == 0, s_plus = -.5 - condassign(s_plus, +x, -half, +half); - // set s_minus to -sign(x)/2, except for case x == 0, s_minus = -.5 - condassign(s_minus, -x, -half, +half); - // set s to sign(x) - return s_plus - s_minus; - } -} -/* $$ - -$head abs$$ -This $cref/required/base_require/$$ function uses the adolc $code fabs$$ -function: -$codep */ -namespace CppAD { - inline adouble abs(const adouble& x) - { return fabs(x); } -} -/* $$ - -$head pow$$ -This $cref/required/base_require/$$ function -is defined by the Adolc package for the $code adouble$$ base case. - -$head numeric_limits$$ -The following defines the CppAD $cref numeric_limits$$ -for the type $code adouble$$: -$codep */ -namespace CppAD { - CPPAD_NUMERIC_LIMITS(double, adouble) -} -/* $$ -$end -*/ -# endif - diff --git a/ct_core/include/ct/external/cppad/example/cppad_eigen.hpp b/ct_core/include/ct/external/cppad/example/cppad_eigen.hpp deleted file mode 100644 index a44a82fa0..000000000 --- a/ct_core/include/ct/external/cppad/example/cppad_eigen.hpp +++ /dev/null @@ -1,180 +0,0 @@ -// $Id: cppad_eigen.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_CPPAD_EIGEN_HPP -# define CPPAD_CPPAD_EIGEN_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin cppad_eigen.hpp$$ -$spell - impl - typename - Real Real - inline - neg - eps - plugin - atan - Num - acos - asin - CppAD - std::numeric - enum - Mul - Eigen - cppad.hpp - namespace - struct - typedef - const - imag - sqrt - exp - cos -$$ -$section Enable Use of Eigen Linear Algebra Package with CppAD$$ - -$head Syntax$$ -$codei%# include %$$ -$children% - cppad/example/eigen_plugin.hpp% - example/eigen_array.cpp% - example/eigen_det.cpp -%$$ - -$head Purpose$$ -Enables the use of the -$href%http://eigen.tuxfamily.org%eigen%$$ -linear algebra package with the type $icode%AD<%Base%>%$$. - -$head Example$$ -The files $cref eigen_array.cpp$$ and $cref eigen_det.cpp$$ -contain an example and test of this include file. -It returns true if it succeeds and false otherwise. - -$head Include Files$$ -The file $code cppad_eigen.hpp$$ includes both -$code $$ and $code $$. -In addition, -The file $cref eigen_plugin.hpp$$ -is used to define $code value_type$$ -in the Eigen matrix class definition so its vectors are -$cref/simple vectors/SimpleVector/$$. -$codep */ -# define EIGEN_MATRIXBASE_PLUGIN -# include -# include -/* $$ -$head Eigen NumTraits$$ -Eigen needs the following definitions to work properly -with $codei%AD<%Base%>%$$ scalars: -$codep */ -namespace Eigen { - template struct NumTraits< CppAD::AD > - { // type that corresponds to the real part of an AD value - typedef CppAD::AD Real; - // type for AD operations that result in non-integer values - typedef CppAD::AD NonInteger; - // type for nested value inside an AD expression tree - typedef CppAD::AD Nested; - - typedef CppAD::AD Literal; - - enum { - // does not support complex Base types - IsComplex = 0 , - // does not support integer Base types - IsInteger = 0 , - // only support signed Base types - IsSigned = 1 , - // must initialize an AD object - RequireInitialization = 1 , - // computational cost of the corresponding operations - ReadCost = 1 , - AddCost = 2 , - MulCost = 2 - }; - - // machine epsilon with type of real part of x - // (use assumption that Base is not complex) - static CppAD::AD epsilon(void) - { return CppAD::numeric_limits< CppAD::AD >::epsilon(); } - - // relaxed version of machine epsilon for comparison of different - // operations that should result in the same value - static CppAD::AD dummy_precision(void) - { return 100. * - CppAD::numeric_limits< CppAD::AD >::epsilon(); - } - - // minimum normalized positive value - static CppAD::AD lowest(void) - { return CppAD::numeric_limits< CppAD::AD >::min(); } - - // maximum finite value - static CppAD::AD highest(void) - { return CppAD::numeric_limits< CppAD::AD >::max(); } - - static const int digits10(void) - { return std::numeric_limits::digits10; } - - - }; -} -/* $$ -$head CppAD Namespace$$ -Eigen also needs the following definitions to work properly -with $codei%AD<%Base%>%$$ scalars: -$codep */ -namespace CppAD { - // functions that return references - template const AD& conj(const AD& x) - { return x; } - template const AD& real(const AD& x) - { return x; } - - // functions that return values (note abs is defined by cppad.hpp) - template AD imag(const AD& x) - { return CppAD::AD(0.); } - template AD abs2(const AD& x) - { return x * x; } -} - - -#if EIGEN_VERSION_AT_LEAST(3,3,0) - // no significant decimals needed for Eigen 3.3 -#else -namespace Eigen { - namespace internal { - - template - struct significant_decimals_default_impl< CppAD::AD, false> - { typedef CppAD::AD Scalar; - - typedef typename NumTraits::Real RealScalar; - static inline int run() - { Scalar neg_log_eps = - log( - NumTraits::epsilon() - ); - int ceil_neg_log_eps = Integer( neg_log_eps ); - if( Scalar(ceil_neg_log_eps) < neg_log_eps ) - ceil_neg_log_eps++; - return ceil_neg_log_eps; - } - }; - } -} -#endif - -/* $$ -$end -*/ -# endif diff --git a/ct_core/include/ct/external/cppad/example/eigen_cholesky.hpp b/ct_core/include/ct/external/cppad/example/eigen_cholesky.hpp deleted file mode 100644 index c0f4da48a..000000000 --- a/ct_core/include/ct/external/cppad/example/eigen_cholesky.hpp +++ /dev/null @@ -1,373 +0,0 @@ -// $Id$ -# ifndef CPPAD_EXAMPLE_EIGEN_CHOLESKY_HPP -# define CPPAD_EXAMPLE_EIGEN_CHOLESKY_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin atomic_eigen_cholesky.hpp$$ -$spell - Eigen - Taylor - Cholesky - op -$$ - -$section Atomic Eigen Cholesky Factorization Class$$ - -$head Purpose$$ -Construct an atomic operation that computes a lower triangular matrix -$latex L $$ such that $latex L L^\R{T} = A$$ -for any positive integer $latex p$$ -and symmetric positive definite matrix $latex A \in \B{R}^{p \times p}$$. - -$head Start Class Definition$$ -$srccode%cpp% */ -# include -# include - - -/* %$$ -$head Public$$ - -$subhead Types$$ -$srccode%cpp% */ -namespace { // BEGIN_EMPTY_NAMESPACE - -template -class atomic_eigen_cholesky : public CppAD::atomic_base { -public: - // ----------------------------------------------------------- - // type of elements during calculation of derivatives - typedef Base scalar; - // type of elements during taping - typedef CppAD::AD ad_scalar; - // - // type of matrix during calculation of derivatives - typedef Eigen::Matrix< - scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> matrix; - // type of matrix during taping - typedef Eigen::Matrix< - ad_scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > ad_matrix; - // - // lower triangular scalar matrix - typedef Eigen::TriangularView lower_view; -/* %$$ -$subhead Constructor$$ -$srccode%cpp% */ - // constructor - atomic_eigen_cholesky(void) : CppAD::atomic_base( - "atom_eigen_cholesky" , - CppAD::atomic_base::set_sparsity_enum - ) - { } -/* %$$ -$subhead op$$ -$srccode%cpp% */ - // use atomic operation to invert an AD matrix - ad_matrix op(const ad_matrix& arg) - { size_t nr = size_t( arg.rows() ); - size_t ny = ( (nr + 1 ) * nr ) / 2; - size_t nx = 1 + ny; - assert( nr == size_t( arg.cols() ) ); - // ------------------------------------------------------------------- - // packed version of arg - CPPAD_TESTVECTOR(ad_scalar) packed_arg(nx); - size_t index = 0; - packed_arg[index++] = ad_scalar( nr ); - // lower triangle of symmetric matrix A - for(size_t i = 0; i < nr; i++) - { for(size_t j = 0; j <= i; j++) - packed_arg[index++] = arg(i, j); - } - assert( index == nx ); - // ------------------------------------------------------------------- - // packed version of result = arg^{-1}. - // This is an atomic_base function call that CppAD uses to - // store the atomic operation on the tape. - CPPAD_TESTVECTOR(ad_scalar) packed_result(ny); - (*this)(packed_arg, packed_result); - // ------------------------------------------------------------------- - // unpack result matrix L - ad_matrix result = ad_matrix::Zero(nr, nr); - index = 0; - for(size_t i = 0; i < nr; i++) - { for(size_t j = 0; j <= i; j++) - result(i, j) = packed_result[index++]; - } - return result; - } - /* %$$ -$head Private$$ - -$subhead Variables$$ -$srccode%cpp% */ -private: - // ------------------------------------------------------------- - // one forward mode vector of matrices for argument and result - CppAD::vector f_arg_, f_result_; - // one reverse mode vector of matrices for argument and result - CppAD::vector r_arg_, r_result_; - // ------------------------------------------------------------- -/* %$$ -$subhead forward$$ -$srccode%cpp% */ - // forward mode routine called by CppAD - virtual bool forward( - // lowest order Taylor coefficient we are evaluating - size_t p , - // highest order Taylor coefficient we are evaluating - size_t q , - // which components of x are variables - const CppAD::vector& vx , - // which components of y are variables - CppAD::vector& vy , - // tx [ j * (q+1) + k ] is x_j^k - const CppAD::vector& tx , - // ty [ i * (q+1) + k ] is y_i^k - CppAD::vector& ty - ) - { size_t n_order = q + 1; - size_t nr = size_t( CppAD::Integer( tx[ 0 * n_order + 0 ] ) ); - size_t ny = ((nr + 1) * nr) / 2; - size_t nx = 1 + ny; - assert( vx.size() == 0 || nx == vx.size() ); - assert( vx.size() == 0 || ny == vy.size() ); - assert( nx * n_order == tx.size() ); - assert( ny * n_order == ty.size() ); - // - // ------------------------------------------------------------------- - // make sure f_arg_ and f_result_ are large enough - assert( f_arg_.size() == f_result_.size() ); - if( f_arg_.size() < n_order ) - { f_arg_.resize(n_order); - f_result_.resize(n_order); - // - for(size_t k = 0; k < n_order; k++) - { f_arg_[k].resize(nr, nr); - f_result_[k].resize(nr, nr); - } - } - // ------------------------------------------------------------------- - // unpack tx into f_arg_ - for(size_t k = 0; k < n_order; k++) - { size_t index = 1; - // unpack arg values for this order - for(size_t i = 0; i < nr; i++) - { for(size_t j = 0; j <= i; j++) - { f_arg_[k](i, j) = tx[ index * n_order + k ]; - f_arg_[k](j, i) = f_arg_[k](i, j); - index++; - } - } - } - // ------------------------------------------------------------------- - // result for each order - // (we could avoid recalculting f_result_[k] for k=0,...,p-1) - // - Eigen::LLT cholesky(f_arg_[0]); - f_result_[0] = cholesky.matrixL(); - lower_view L_0 = f_result_[0].template triangularView(); - for(size_t k = 1; k < n_order; k++) - { // initialize sum as A_k - matrix f_sum = f_arg_[k]; - // compute A_k - B_k - for(size_t ell = 1; ell < k; ell++) - f_sum -= f_result_[ell] * f_result_[k-ell].transpose(); - // compute L_0^{-1} * (A_k - B_k) * L_0^{-T} - matrix temp = L_0.template solve(f_sum); - temp = L_0.transpose().template solve(temp); - // divide the diagonal by 2 - for(size_t i = 0; i < nr; i++) - temp(i, i) /= scalar(2.0); - // L_k = L_0 * low[ L_0^{-1} * (A_k - B_k) * L_0^{-T} ] - lower_view view = temp.template triangularView(); - f_result_[k] = f_result_[0] * view; - } - // ------------------------------------------------------------------- - // pack result_ into ty - for(size_t k = 0; k < n_order; k++) - { size_t index = 0; - for(size_t i = 0; i < nr; i++) - { for(size_t j = 0; j <= i; j++) - { ty[ index * n_order + k ] = f_result_[k](i, j); - index++; - } - } - } - // ------------------------------------------------------------------- - // check if we are computing vy - if( vx.size() == 0 ) - return true; - // ------------------------------------------------------------------ - // This is a very dumb algorithm that over estimates which - // elements of the inverse are variables (which is not efficient). - bool var = false; - for(size_t i = 0; i < ny; i++) - var |= vx[1 + i]; - for(size_t i = 0; i < ny; i++) - vy[i] = var; - // - return true; - } -/* %$$ -$subhead reverse$$ -$srccode%cpp% */ - // reverse mode routine called by CppAD - virtual bool reverse( - // highest order Taylor coefficient that we are computing derivative of - size_t q , - // forward mode Taylor coefficients for x variables - const CppAD::vector& tx , - // forward mode Taylor coefficients for y variables - const CppAD::vector& ty , - // upon return, derivative of G[ F[ {x_j^k} ] ] w.r.t {x_j^k} - CppAD::vector& px , - // derivative of G[ {y_i^k} ] w.r.t. {y_i^k} - const CppAD::vector& py - ) - { size_t n_order = q + 1; - size_t nr = size_t( CppAD::Integer( tx[ 0 * n_order + 0 ] ) ); - size_t ny = ( (nr + 1 ) * nr ) / 2; - size_t nx = 1 + ny; - // - assert( nx * n_order == tx.size() ); - assert( ny * n_order == ty.size() ); - assert( px.size() == tx.size() ); - assert( py.size() == ty.size() ); - // ------------------------------------------------------------------- - // make sure f_arg_ is large enough - assert( f_arg_.size() == f_result_.size() ); - // must have previous run forward with order >= n_order - assert( f_arg_.size() >= n_order ); - // ------------------------------------------------------------------- - // make sure r_arg_, r_result_ are large enough - assert( r_arg_.size() == r_result_.size() ); - if( r_arg_.size() < n_order ) - { r_arg_.resize(n_order); - r_result_.resize(n_order); - // - for(size_t k = 0; k < n_order; k++) - { r_arg_[k].resize(nr, nr); - r_result_[k].resize(nr, nr); - } - } - // ------------------------------------------------------------------- - // unpack tx into f_arg_ - for(size_t k = 0; k < n_order; k++) - { size_t index = 1; - // unpack arg values for this order - for(size_t i = 0; i < nr; i++) - { for(size_t j = 0; j <= i; j++) - { f_arg_[k](i, j) = tx[ index * n_order + k ]; - f_arg_[k](j, i) = f_arg_[k](i, j); - index++; - } - } - } - // ------------------------------------------------------------------- - // unpack py into r_result_ - for(size_t k = 0; k < n_order; k++) - { r_result_[k] = matrix::Zero(nr, nr); - size_t index = 0; - for(size_t i = 0; i < nr; i++) - { for(size_t j = 0; j <= i; j++) - { r_result_[k](i, j) = py[ index * n_order + k ]; - index++; - } - } - } - // ------------------------------------------------------------------- - // initialize r_arg_ as zero - for(size_t k = 0; k < n_order; k++) - r_arg_[k] = matrix::Zero(nr, nr); - // ------------------------------------------------------------------- - // matrix reverse mode calculation - lower_view L_0 = f_result_[0].template triangularView(); - // - for(size_t k1 = n_order; k1 > 1; k1--) - { size_t k = k1 - 1; - // - // L_0^T * bar{L}_k - matrix tmp1 = L_0.transpose() * r_result_[k]; - // - //low[ L_0^T * bar{L}_k ] - for(size_t i = 0; i < nr; i++) - tmp1(i, i) /= scalar(2.0); - matrix tmp2 = tmp1.template triangularView(); - // - // L_0^{-T} low[ L_0^T * bar{L}_k ] - tmp1 = L_0.transpose().template solve( tmp2 ); - // - // M_k = L_0^{-T} * low[ L_0^T * bar{L}_k ]^{T} L_0^{-1} - matrix M_k = L_0.transpose().template - solve( tmp1.transpose() ); - // - // remove L_k and compute bar{B}_k - matrix barB_k = scalar(0.5) * ( M_k + M_k.transpose() ); - r_arg_[k] += barB_k; - barB_k = scalar(-1.0) * barB_k; - // - // 2.0 * lower( bar{B}_k L_k ) - matrix temp = scalar(2.0) * barB_k * f_result_[k]; - temp = temp.template triangularView(); - // - // remove C_k - r_result_[0] += temp; - // - // remove B_k - for(size_t ell = 1; ell < k; ell++) - { // bar{L}_ell = 2 * lower( \bar{B}_k * L_{k-ell} ) - temp = scalar(2.0) * barB_k * f_result_[k-ell]; - r_result_[ell] += temp.template triangularView(); - } - } - // M_0 = L_0^{-T} * low[ L_0^T * bar{L}_0 ]^{T} L_0^{-1} - matrix M_0 = L_0.transpose() * r_result_[0]; - for(size_t i = 0; i < nr; i++) - M_0(i, i) /= scalar(2.0); - M_0 = M_0.template triangularView(); - M_0 = L_0.template solve( M_0 ); - M_0 = L_0.transpose().template solve( M_0 ); - // remove L_0 - r_arg_[0] += scalar(0.5) * ( M_0 + M_0.transpose() ); - // ------------------------------------------------------------------- - // pack r_arg into px - // note that only the lower triangle of barA_k is stored in px - for(size_t k = 0; k < n_order; k++) - { size_t index = 0; - px[ index * n_order + k ] = 0.0; - index++; - for(size_t i = 0; i < nr; i++) - { for(size_t j = 0; j < i; j++) - { px[ index * n_order + k ] = 2.0 * r_arg_[k](i, j); - index++; - } - px[ index * n_order + k] = r_arg_[k](i, i); - index++; - } - } - // ------------------------------------------------------------------- - return true; - } -/* %$$ -$head End Class Definition$$ -$srccode%cpp% */ -}; // End of atomic_eigen_cholesky class - -} // END_EMPTY_NAMESPACE -/* %$$ -$end -*/ - - -# endif diff --git a/ct_core/include/ct/external/cppad/example/eigen_mat_inv.hpp b/ct_core/include/ct/external/cppad/example/eigen_mat_inv.hpp deleted file mode 100644 index 3f07a2963..000000000 --- a/ct_core/include/ct/external/cppad/example/eigen_mat_inv.hpp +++ /dev/null @@ -1,392 +0,0 @@ -// $Id$ -# ifndef CPPAD_EXAMPLE_EIGEN_MAT_INV_HPP -# define CPPAD_EXAMPLE_EIGEN_MAT_INV_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin atomic_eigen_mat_inv.hpp$$ -$spell - Eigen - Taylor -$$ - -$section Atomic Eigen Matrix Inversion Class$$ - -$head Purpose$$ -Construct an atomic operation that computes the matrix inverse -$latex R = A^{-1}$$ -for any positive integer $latex p$$ -and invertible matrix $latex A \in \B{R}^{p \times p}$$. - -$head Matrix Dimensions$$ -This example puts the matrix dimension $latex p$$ -in the atomic function arguments, -instead of the $cref/constructor/atomic_ctor/$$, -so it can be different for different calls to the atomic function. - -$head Theory$$ - -$subhead Forward$$ -The zero order forward mode Taylor coefficient is give by -$latex \[ - R_0 = A_0^{-1} -\]$$ -For $latex k = 1 , \ldots$$, -the $th k$$ order Taylor coefficient of $latex A R$$ is given by -$latex \[ - 0 = \sum_{\ell=0}^k A_\ell R_{k-\ell} -\] $$ -Solving for $latex R_k$$ in terms of the coefficients -for $latex A$$ and the lower order coefficients for $latex R$$ we have -$latex \[ - R_k = - R_0 \left( \sum_{\ell=1}^k A_\ell R_{k-\ell} \right) -\] $$ -Furthermore, once we have $latex R_k$$ we can compute the sum using -$latex \[ - A_0 R_k = - \left( \sum_{\ell=1}^k A_\ell R_{k-\ell} \right) -\] $$ - - -$subhead Product of Three Matrices$$ -Suppose $latex \bar{E}$$ is the derivative of the -scalar value function $latex s(E)$$ with respect to $latex E$$; i.e., -$latex \[ - \bar{E}_{i,j} = \frac{ \partial s } { \partial E_{i,j} } -\] $$ -Also suppose that $latex t$$ is a scalar valued argument and -$latex \[ - E(t) = B(t) C(t) D(t) -\] $$ -It follows that -$latex \[ - E'(t) = B'(t) C(t) D(t) + B(t) C'(t) D(t) + B(t) C(t) D'(t) -\] $$ - -$latex \[ - (s \circ E)'(t) - = - \R{tr} [ \bar{E}^\R{T} E'(t) ] -\] $$ -$latex \[ - = - \R{tr} [ \bar{E}^\R{T} B'(t) C(t) D(t) ] + - \R{tr} [ \bar{E}^\R{T} B(t) C'(t) D(t) ] + - \R{tr} [ \bar{E}^\R{T} B(t) C(t) D'(t) ] -\] $$ -$latex \[ - = - \R{tr} [ B(t) D(t) \bar{E}^\R{T} B'(t) ] + - \R{tr} [ D(t) \bar{E}^\R{T} B(t) C'(t) ] + - \R{tr} [ \bar{E}^\R{T} B(t) C(t) D'(t) ] -\] $$ -$latex \[ - \bar{B} = \bar{E} (C D)^\R{T} \W{,} - \bar{C} = B^\R{T} \bar{E} D^\R{T} \W{,} - \bar{D} = (B C)^\R{T} \bar{E} -\] $$ - -$subhead Reverse$$ -For $latex k > 0$$, reverse mode -eliminates $latex R_k$$ and expresses the function values -$latex s$$ in terms of the coefficients of $latex A$$ -and the lower order coefficients of $latex R$$. -The effect on $latex \bar{R}_0$$ -(of eliminating $latex R_k$$) is -$latex \[ -\bar{R}_0 -= \bar{R}_0 - \bar{R}_k \left( \sum_{\ell=1}^k A_\ell R_{k-\ell} \right)^\R{T} -= \bar{R}_0 + \bar{R}_k ( A_0 R_k )^\R{T} -\] $$ -For $latex \ell = 1 , \ldots , k$$, -the effect on $latex \bar{R}_{k-\ell}$$ and $latex A_\ell$$ -(of eliminating $latex R_k$$) is -$latex \[ -\bar{A}_\ell = \bar{A}_\ell - R_0^\R{T} \bar{R}_k R_{k-\ell}^\R{T} -\] $$ -$latex \[ -\bar{R}_{k-\ell} = \bar{R}_{k-\ell} - ( R_0 A_\ell )^\R{T} \bar{R}_k -\] $$ -We note that -$latex \[ - R_0 '(t) A_0 (t) + R_0 (t) A_0 '(t) = 0 -\] $$ -$latex \[ - R_0 '(t) = - R_0 (t) A_0 '(t) R_0 (t) -\] $$ -The reverse mode formula that eliminates $latex R_0$$ is -$latex \[ - \bar{A}_0 - = \bar{A}_0 - R_0^\R{T} \bar{R}_0 R_0^\R{T} -\]$$ - -$nospell - -$head Start Class Definition$$ -$srccode%cpp% */ -# include -# include -# include - - - -/* %$$ -$head Public$$ - -$subhead Types$$ -$srccode%cpp% */ -namespace { // BEGIN_EMPTY_NAMESPACE - -template -class atomic_eigen_mat_inv : public CppAD::atomic_base { -public: - // ----------------------------------------------------------- - // type of elements during calculation of derivatives - typedef Base scalar; - // type of elements during taping - typedef CppAD::AD ad_scalar; - // type of matrix during calculation of derivatives - typedef Eigen::Matrix< - scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> matrix; - // type of matrix during taping - typedef Eigen::Matrix< - ad_scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > ad_matrix; -/* %$$ -$subhead Constructor$$ -$srccode%cpp% */ - // constructor - atomic_eigen_mat_inv(void) : CppAD::atomic_base( - "atom_eigen_mat_inv" , - CppAD::atomic_base::set_sparsity_enum - ) - { } -/* %$$ -$subhead op$$ -$srccode%cpp% */ - // use atomic operation to invert an AD matrix - ad_matrix op(const ad_matrix& arg) - { size_t nr = size_t( arg.rows() ); - size_t ny = nr * nr; - size_t nx = 1 + ny; - assert( nr == size_t( arg.cols() ) ); - // ------------------------------------------------------------------- - // packed version of arg - CPPAD_TESTVECTOR(ad_scalar) packed_arg(nx); - packed_arg[0] = ad_scalar( nr ); - for(size_t i = 0; i < ny; i++) - packed_arg[1 + i] = arg.data()[i]; - // ------------------------------------------------------------------- - // packed version of result = arg^{-1}. - // This is an atomic_base function call that CppAD uses to - // store the atomic operation on the tape. - CPPAD_TESTVECTOR(ad_scalar) packed_result(ny); - (*this)(packed_arg, packed_result); - // ------------------------------------------------------------------- - // unpack result matrix - ad_matrix result(nr, nr); - for(size_t i = 0; i < ny; i++) - result.data()[i] = packed_result[i]; - return result; - } - /* %$$ -$head Private$$ - -$subhead Variables$$ -$srccode%cpp% */ -private: - // ------------------------------------------------------------- - // one forward mode vector of matrices for argument and result - CppAD::vector f_arg_, f_result_; - // one reverse mode vector of matrices for argument and result - CppAD::vector r_arg_, r_result_; - // ------------------------------------------------------------- -/* %$$ -$subhead forward$$ -$srccode%cpp% */ - // forward mode routine called by CppAD - virtual bool forward( - // lowest order Taylor coefficient we are evaluating - size_t p , - // highest order Taylor coefficient we are evaluating - size_t q , - // which components of x are variables - const CppAD::vector& vx , - // which components of y are variables - CppAD::vector& vy , - // tx [ j * (q+1) + k ] is x_j^k - const CppAD::vector& tx , - // ty [ i * (q+1) + k ] is y_i^k - CppAD::vector& ty - ) - { size_t n_order = q + 1; - size_t nr = size_t( CppAD::Integer( tx[ 0 * n_order + 0 ] ) ); - size_t ny = nr * nr; - size_t nx = 1 + ny; - assert( vx.size() == 0 || nx == vx.size() ); - assert( vx.size() == 0 || ny == vy.size() ); - assert( nx * n_order == tx.size() ); - assert( ny * n_order == ty.size() ); - // - // ------------------------------------------------------------------- - // make sure f_arg_ and f_result_ are large enough - assert( f_arg_.size() == f_result_.size() ); - if( f_arg_.size() < n_order ) - { f_arg_.resize(n_order); - f_result_.resize(n_order); - // - for(size_t k = 0; k < n_order; k++) - { f_arg_[k].resize(nr, nr); - f_result_[k].resize(nr, nr); - } - } - // ------------------------------------------------------------------- - // unpack tx into f_arg_ - for(size_t k = 0; k < n_order; k++) - { // unpack arg values for this order - for(size_t i = 0; i < ny; i++) - f_arg_[k].data()[i] = tx[ (1 + i) * n_order + k ]; - } - // ------------------------------------------------------------------- - // result for each order - // (we could avoid recalculting f_result_[k] for k=0,...,p-1) - // - f_result_[0] = f_arg_[0].inverse(); - for(size_t k = 1; k < n_order; k++) - { // initialize sum - matrix f_sum = matrix::Zero(nr, nr); - // compute sum - for(size_t ell = 1; ell <= k; ell++) - f_sum -= f_arg_[ell] * f_result_[k-ell]; - // result_[k] = arg_[0]^{-1} * sum_ - f_result_[k] = f_result_[0] * f_sum; - } - // ------------------------------------------------------------------- - // pack result_ into ty - for(size_t k = 0; k < n_order; k++) - { for(size_t i = 0; i < ny; i++) - ty[ i * n_order + k ] = f_result_[k].data()[i]; - } - // ------------------------------------------------------------------- - // check if we are computing vy - if( vx.size() == 0 ) - return true; - // ------------------------------------------------------------------ - // This is a very dumb algorithm that over estimates which - // elements of the inverse are variables (which is not efficient). - bool var = false; - for(size_t i = 0; i < ny; i++) - var |= vx[1 + i]; - for(size_t i = 0; i < ny; i++) - vy[i] = var; - return true; - } -/* %$$ -$subhead reverse$$ -$srccode%cpp% */ - // reverse mode routine called by CppAD - virtual bool reverse( - // highest order Taylor coefficient that we are computing derivative of - size_t q , - // forward mode Taylor coefficients for x variables - const CppAD::vector& tx , - // forward mode Taylor coefficients for y variables - const CppAD::vector& ty , - // upon return, derivative of G[ F[ {x_j^k} ] ] w.r.t {x_j^k} - CppAD::vector& px , - // derivative of G[ {y_i^k} ] w.r.t. {y_i^k} - const CppAD::vector& py - ) - { size_t n_order = q + 1; - size_t nr = size_t( CppAD::Integer( tx[ 0 * n_order + 0 ] ) ); - size_t ny = nr * nr; - size_t nx = 1 + ny; - // - assert( nx * n_order == tx.size() ); - assert( ny * n_order == ty.size() ); - assert( px.size() == tx.size() ); - assert( py.size() == ty.size() ); - // ------------------------------------------------------------------- - // make sure f_arg_ is large enough - assert( f_arg_.size() == f_result_.size() ); - // must have previous run forward with order >= n_order - assert( f_arg_.size() >= n_order ); - // ------------------------------------------------------------------- - // make sure r_arg_, r_result_ are large enough - assert( r_arg_.size() == r_result_.size() ); - if( r_arg_.size() < n_order ) - { r_arg_.resize(n_order); - r_result_.resize(n_order); - // - for(size_t k = 0; k < n_order; k++) - { r_arg_[k].resize(nr, nr); - r_result_[k].resize(nr, nr); - } - } - // ------------------------------------------------------------------- - // unpack tx into f_arg_ - for(size_t k = 0; k < n_order; k++) - { // unpack arg values for this order - for(size_t i = 0; i < ny; i++) - f_arg_[k].data()[i] = tx[ (1 + i) * n_order + k ]; - } - // ------------------------------------------------------------------- - // unpack py into r_result_ - for(size_t k = 0; k < n_order; k++) - { for(size_t i = 0; i < ny; i++) - r_result_[k].data()[i] = py[ i * n_order + k ]; - } - // ------------------------------------------------------------------- - // initialize r_arg_ as zero - for(size_t k = 0; k < n_order; k++) - r_arg_[k] = matrix::Zero(nr, nr); - // ------------------------------------------------------------------- - // matrix reverse mode calculation - // - for(size_t k1 = n_order; k1 > 1; k1--) - { size_t k = k1 - 1; - // bar{R}_0 = bar{R}_0 + bar{R}_k (A_0 R_k)^T - r_result_[0] += - r_result_[k] * f_result_[k].transpose() * f_arg_[0].transpose(); - // - for(size_t ell = 1; ell <= k; ell++) - { // bar{A}_l = bar{A}_l - R_0^T bar{R}_k R_{k-l}^T - r_arg_[ell] -= f_result_[0].transpose() - * r_result_[k] * f_result_[k-ell].transpose(); - // bar{R}_{k-l} = bar{R}_{k-1} - (R_0 A_l)^T bar{R}_k - r_result_[k-ell] -= f_arg_[ell].transpose() - * f_result_[0].transpose() * r_result_[k]; - } - } - r_arg_[0] -= - f_result_[0].transpose() * r_result_[0] * f_result_[0].transpose(); - // ------------------------------------------------------------------- - // pack r_arg into px - for(size_t k = 0; k < n_order; k++) - { for(size_t i = 0; i < ny; i++) - px[ (1 + i) * n_order + k ] = r_arg_[k].data()[i]; - } - // - return true; - } -/* %$$ -$head End Class Definition$$ -$srccode%cpp% */ -}; // End of atomic_eigen_mat_inv class - -} // END_EMPTY_NAMESPACE -/* %$$ -$$ $comment end nospell$$ -$end -*/ - - -# endif diff --git a/ct_core/include/ct/external/cppad/example/eigen_mat_mul.hpp b/ct_core/include/ct/external/cppad/example/eigen_mat_mul.hpp deleted file mode 100644 index e88587a44..000000000 --- a/ct_core/include/ct/external/cppad/example/eigen_mat_mul.hpp +++ /dev/null @@ -1,653 +0,0 @@ -// $Id$ -# ifndef CPPAD_EXAMPLE_EIGEN_MAT_MUL_HPP -# define CPPAD_EXAMPLE_EIGEN_MAT_MUL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin atomic_eigen_mat_mul.hpp$$ -$spell - Eigen - Taylor - nr - nc -$$ - -$section Atomic Eigen Matrix Multiply Class$$ - -$head See Also$$ -$cref atomic_mat_mul.hpp$$ - -$head Purpose$$ -Construct an atomic operation that computes the matrix product, -$latex R = A \times B$$ -for any positive integers $latex r$$, $latex m$$, $latex c$$, -and any $latex A \in \B{R}^{r \times m}$$, -$latex B \in \B{R}^{m \times c}$$. - -$head Matrix Dimensions$$ -This example puts the matrix dimensions in the atomic function arguments, -instead of the $cref/constructor/atomic_ctor/$$, so that they can -be different for different calls to the atomic function. -These dimensions are: -$table -$icode nr_left$$ - $cnext number of rows in the left matrix; i.e, $latex r$$ $rend -$icode n_middle$$ - $cnext rows in the left matrix and columns in right; i.e, $latex m$$ $rend -$icode nc_right$$ - $cnext number of columns in the right matrix; i.e., $latex c$$ -$tend - -$head Theory$$ - -$subhead Forward$$ -For $latex k = 0 , \ldots $$, the $th k$$ order Taylor coefficient -$latex R_k$$ is given by -$latex \[ - R_k = \sum_{\ell = 0}^{k} A_\ell B_{k-\ell} -\] $$ - -$subhead Product of Two Matrices$$ -Suppose $latex \bar{E}$$ is the derivative of the -scalar value function $latex s(E)$$ with respect to $latex E$$; i.e., -$latex \[ - \bar{E}_{i,j} = \frac{ \partial s } { \partial E_{i,j} } -\] $$ -Also suppose that $latex t$$ is a scalar valued argument and -$latex \[ - E(t) = C(t) D(t) -\] $$ -It follows that -$latex \[ - E'(t) = C'(t) D(t) + C(t) D'(t) -\] $$ - -$latex \[ - (s \circ E)'(t) - = - \R{tr} [ \bar{E}^\R{T} E'(t) ] -\] $$ -$latex \[ - = - \R{tr} [ \bar{E}^\R{T} C'(t) D(t) ] + - \R{tr} [ \bar{E}^\R{T} C(t) D'(t) ] -\] $$ -$latex \[ - = - \R{tr} [ D(t) \bar{E}^\R{T} C'(t) ] + - \R{tr} [ \bar{E}^\R{T} C(t) D'(t) ] -\] $$ -$latex \[ - \bar{C} = \bar{E} D^\R{T} \W{,} - \bar{D} = C^\R{T} \bar{E} -\] $$ - -$subhead Reverse$$ -Reverse mode eliminates $latex R_k$$ as follows: -for $latex \ell = 0, \ldots , k-1$$, -$latex \[ -\bar{A}_\ell = \bar{A}_\ell + \bar{R}_k B_{k-\ell}^\R{T} -\] $$ -$latex \[ -\bar{B}_{k-\ell} = \bar{B}_{k-\ell} + A_\ell^\R{T} \bar{R}_k -\] $$ - - -$nospell - -$head Start Class Definition$$ -$srccode%cpp% */ -# include -# include - - -/* %$$ -$head Public$$ - -$subhead Types$$ -$srccode%cpp% */ -namespace { // BEGIN_EMPTY_NAMESPACE - -template -class atomic_eigen_mat_mul : public CppAD::atomic_base { -public: - // ----------------------------------------------------------- - // type of elements during calculation of derivatives - typedef Base scalar; - // type of elements during taping - typedef CppAD::AD ad_scalar; - // type of matrix during calculation of derivatives - typedef Eigen::Matrix< - scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> matrix; - // type of matrix during taping - typedef Eigen::Matrix< - ad_scalar, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > ad_matrix; -/* %$$ -$subhead Constructor$$ -$srccode%cpp% */ - // constructor - atomic_eigen_mat_mul(void) : CppAD::atomic_base( - "atom_eigen_mat_mul" , - CppAD::atomic_base::set_sparsity_enum - ) - { } -/* %$$ -$subhead op$$ -$srccode%cpp% */ - // use atomic operation to multiply two AD matrices - ad_matrix op( - const ad_matrix& left , - const ad_matrix& right ) - { size_t nr_left = size_t( left.rows() ); - size_t n_middle = size_t( left.cols() ); - size_t nc_right = size_t( right.cols() ); - assert( n_middle == size_t( right.rows() ) ); -# ifndef NDEBUG - size_t nx = 3 + (nr_left + nc_right) * n_middle; - size_t ny = nr_left * nc_right; -# endif - size_t n_left = nr_left * n_middle; - size_t n_right = n_middle * nc_right; - size_t n_result = nr_left * nc_right; - // - assert( 3 + n_left + n_right == nx ); - assert( n_result == ny ); - // ----------------------------------------------------------------- - // packed version of left and right - CPPAD_TESTVECTOR(ad_scalar) packed_arg(nx); - // - packed_arg[0] = ad_scalar( nr_left ); - packed_arg[1] = ad_scalar( n_middle ); - packed_arg[2] = ad_scalar( nc_right ); - for(size_t i = 0; i < n_left; i++) - packed_arg[3 + i] = left.data()[i]; - for(size_t i = 0; i < n_right; i++) - packed_arg[ 3 + n_left + i ] = right.data()[i]; - // ------------------------------------------------------------------ - // Packed version of result = left * right. - // This as an atomic_base funciton call that CppAD uses - // to store the atomic operation on the tape. - CPPAD_TESTVECTOR(ad_scalar) packed_result(ny); - (*this)(packed_arg, packed_result); - // ------------------------------------------------------------------ - // unpack result matrix - ad_matrix result(nr_left, nc_right); - for(size_t i = 0; i < n_result; i++) - result.data()[i] = packed_result[ i ]; - // - return result; - } -/* %$$ -$head Private$$ - -$subhead Variables$$ -$srccode%cpp% */ -private: - // ------------------------------------------------------------- - // one forward mode vector of matrices for left, right, and result - CppAD::vector f_left_, f_right_, f_result_; - // one reverse mode vector of matrices for left, right, and result - CppAD::vector r_left_, r_right_, r_result_; - // ------------------------------------------------------------- -/* %$$ -$subhead forward$$ -$srccode%cpp% */ - // forward mode routine called by CppAD - virtual bool forward( - // lowest order Taylor coefficient we are evaluating - size_t p , - // highest order Taylor coefficient we are evaluating - size_t q , - // which components of x are variables - const CppAD::vector& vx , - // which components of y are variables - CppAD::vector& vy , - // tx [ 3 + j * (q+1) + k ] is x_j^k - const CppAD::vector& tx , - // ty [ i * (q+1) + k ] is y_i^k - CppAD::vector& ty - ) - { size_t n_order = q + 1; - size_t nr_left = size_t( CppAD::Integer( tx[ 0 * n_order + 0 ] ) ); - size_t n_middle = size_t( CppAD::Integer( tx[ 1 * n_order + 0 ] ) ); - size_t nc_right = size_t( CppAD::Integer( tx[ 2 * n_order + 0 ] ) ); -# ifndef NDEBUG - size_t nx = 3 + (nr_left + nc_right) * n_middle; - size_t ny = nr_left * nc_right; -# endif - // - assert( vx.size() == 0 || nx == vx.size() ); - assert( vx.size() == 0 || ny == vy.size() ); - assert( nx * n_order == tx.size() ); - assert( ny * n_order == ty.size() ); - // - size_t n_left = nr_left * n_middle; - size_t n_right = n_middle * nc_right; - size_t n_result = nr_left * nc_right; - assert( 3 + n_left + n_right == nx ); - assert( n_result == ny ); - // - // ------------------------------------------------------------------- - // make sure f_left_, f_right_, and f_result_ are large enough - assert( f_left_.size() == f_right_.size() ); - assert( f_left_.size() == f_result_.size() ); - if( f_left_.size() < n_order ) - { f_left_.resize(n_order); - f_right_.resize(n_order); - f_result_.resize(n_order); - // - for(size_t k = 0; k < n_order; k++) - { f_left_[k].resize(nr_left, n_middle); - f_right_[k].resize(n_middle, nc_right); - f_result_[k].resize(nr_left, nc_right); - } - } - // ------------------------------------------------------------------- - // unpack tx into f_left and f_right - for(size_t k = 0; k < n_order; k++) - { // unpack left values for this order - for(size_t i = 0; i < n_left; i++) - f_left_[k].data()[i] = tx[ (3 + i) * n_order + k ]; - // - // unpack right values for this order - for(size_t i = 0; i < n_right; i++) - f_right_[k].data()[i] = tx[ ( 3 + n_left + i) * n_order + k ]; - } - // ------------------------------------------------------------------- - // result for each order - // (we could avoid recalculting f_result_[k] for k=0,...,p-1) - for(size_t k = 0; k < n_order; k++) - { // result[k] = sum_ell left[ell] * right[k-ell] - f_result_[k] = matrix::Zero(nr_left, nc_right); - for(size_t ell = 0; ell <= k; ell++) - f_result_[k] += f_left_[ell] * f_right_[k-ell]; - } - // ------------------------------------------------------------------- - // pack result_ into ty - for(size_t k = 0; k < n_order; k++) - { for(size_t i = 0; i < n_result; i++) - ty[ i * n_order + k ] = f_result_[k].data()[i]; - } - // ------------------------------------------------------------------ - // check if we are computing vy - if( vx.size() == 0 ) - return true; - // ------------------------------------------------------------------ - // compute variable information for y; i.e., vy - // (note that the constant zero times a variable is a constant) - scalar zero(0.0); - assert( n_order == 1 ); - for(size_t i = 0; i < nr_left; i++) - { for(size_t j = 0; j < nc_right; j++) - { bool var = false; - for(size_t ell = 0; ell < n_middle; ell++) - { // left information - size_t index = 3 + i * n_middle + ell; - bool var_left = vx[index]; - bool nz_left = var_left | (f_left_[0](i, ell) != zero); - // right information - index = 3 + n_left + ell * nc_right + j; - bool var_right = vx[index]; - bool nz_right = var_right | (f_right_[0](ell, j) != zero); - // effect of result - var |= var_left & nz_right; - var |= nz_left & var_right; - } - size_t index = i * nc_right + j; - vy[index] = var; - } - } - return true; - } -/* %$$ -$subhead reverse$$ -$srccode%cpp% */ - // reverse mode routine called by CppAD - virtual bool reverse( - // highest order Taylor coefficient that we are computing derivative of - size_t q , - // forward mode Taylor coefficients for x variables - const CppAD::vector& tx , - // forward mode Taylor coefficients for y variables - const CppAD::vector& ty , - // upon return, derivative of G[ F[ {x_j^k} ] ] w.r.t {x_j^k} - CppAD::vector& px , - // derivative of G[ {y_i^k} ] w.r.t. {y_i^k} - const CppAD::vector& py - ) - { size_t n_order = q + 1; - size_t nr_left = size_t( CppAD::Integer( tx[ 0 * n_order + 0 ] ) ); - size_t n_middle = size_t( CppAD::Integer( tx[ 1 * n_order + 0 ] ) ); - size_t nc_right = size_t( CppAD::Integer( tx[ 2 * n_order + 0 ] ) ); -# ifndef NDEBUG - size_t nx = 3 + (nr_left + nc_right) * n_middle; - size_t ny = nr_left * nc_right; -# endif - // - assert( nx * n_order == tx.size() ); - assert( ny * n_order == ty.size() ); - assert( px.size() == tx.size() ); - assert( py.size() == ty.size() ); - // - size_t n_left = nr_left * n_middle; - size_t n_right = n_middle * nc_right; - size_t n_result = nr_left * nc_right; - assert( 3 + n_left + n_right == nx ); - assert( n_result == ny ); - // ------------------------------------------------------------------- - // make sure f_left_, f_right_ are large enough - assert( f_left_.size() == f_right_.size() ); - assert( f_left_.size() == f_result_.size() ); - // must have previous run forward with order >= n_order - assert( f_left_.size() >= n_order ); - // ------------------------------------------------------------------- - // make sure r_left_, r_right_, and r_result_ are large enough - assert( r_left_.size() == r_right_.size() ); - assert( r_left_.size() == r_result_.size() ); - if( r_left_.size() < n_order ) - { r_left_.resize(n_order); - r_right_.resize(n_order); - r_result_.resize(n_order); - // - for(size_t k = 0; k < n_order; k++) - { r_left_[k].resize(nr_left, n_middle); - r_right_[k].resize(n_middle, nc_right); - r_result_[k].resize(nr_left, nc_right); - } - } - // ------------------------------------------------------------------- - // unpack tx into f_left and f_right - for(size_t k = 0; k < n_order; k++) - { // unpack left values for this order - for(size_t i = 0; i < n_left; i++) - f_left_[k].data()[i] = tx[ (3 + i) * n_order + k ]; - // - // unpack right values for this order - for(size_t i = 0; i < n_right; i++) - f_right_[k].data()[i] = tx[ (3 + n_left + i) * n_order + k ]; - } - // ------------------------------------------------------------------- - // unpack py into r_result_ - for(size_t k = 0; k < n_order; k++) - { for(size_t i = 0; i < n_result; i++) - r_result_[k].data()[i] = py[ i * n_order + k ]; - } - // ------------------------------------------------------------------- - // initialize r_left_ and r_right_ as zero - for(size_t k = 0; k < n_order; k++) - { r_left_[k] = matrix::Zero(nr_left, n_middle); - r_right_[k] = matrix::Zero(n_middle, nc_right); - } - // ------------------------------------------------------------------- - // matrix reverse mode calculation - for(size_t k1 = n_order; k1 > 0; k1--) - { size_t k = k1 - 1; - for(size_t ell = 0; ell <= k; ell++) - { // nr x nm = nr x nc * nc * nm - r_left_[ell] += r_result_[k] * f_right_[k-ell].transpose(); - // nm x nc = nm x nr * nr * nc - r_right_[k-ell] += f_left_[ell].transpose() * r_result_[k]; - } - } - // ------------------------------------------------------------------- - // pack r_left and r_right int px - for(size_t k = 0; k < n_order; k++) - { // dimensions are integer constants - px[ 0 * n_order + k ] = 0.0; - px[ 1 * n_order + k ] = 0.0; - px[ 2 * n_order + k ] = 0.0; - // - // pack left values for this order - for(size_t i = 0; i < n_left; i++) - px[ (3 + i) * n_order + k ] = r_left_[k].data()[i]; - // - // pack right values for this order - for(size_t i = 0; i < n_right; i++) - px[ (3 + i + n_left) * n_order + k] = r_right_[k].data()[i]; - } - // - return true; - } -/* %$$ -$subhead for_sparse_jac$$ -$srccode%cpp% */ - // forward Jacobian sparsity routine called by CppAD - virtual bool for_sparse_jac( - // number of columns in the matrix R - size_t q , - // sparsity pattern for the matrix R - const CppAD::vector< std::set >& r , - // sparsity pattern for the matrix S = f'(x) * R - CppAD::vector< std::set >& s , - const CppAD::vector& x ) - { - size_t nr_left = size_t( CppAD::Integer( x[0] ) ); - size_t n_middle = size_t( CppAD::Integer( x[1] ) ); - size_t nc_right = size_t( CppAD::Integer( x[2] ) ); -# ifndef NDEBUG - size_t nx = 3 + (nr_left + nc_right) * n_middle; - size_t ny = nr_left * nc_right; -# endif - // - assert( nx == r.size() ); - assert( ny == s.size() ); - // - size_t n_left = nr_left * n_middle; - for(size_t i = 0; i < nr_left; i++) - { for(size_t j = 0; j < nc_right; j++) - { // pack index for entry (i, j) in result - size_t i_result = i * nc_right + j; - s[i_result].clear(); - for(size_t ell = 0; ell < n_middle; ell++) - { // pack index for entry (i, ell) in left - size_t i_left = 3 + i * n_middle + ell; - // pack index for entry (ell, j) in right - size_t i_right = 3 + n_left + ell * nc_right + j; - // - s[i_result] = CppAD::set_union(s[i_result], r[i_left] ); - s[i_result] = CppAD::set_union(s[i_result], r[i_right] ); - } - } - } - return true; - } -/* %$$ -$subhead rev_sparse_jac$$ -$srccode%cpp% */ - // reverse Jacobian sparsity routine called by CppAD - virtual bool rev_sparse_jac( - // number of columns in the matrix R^T - size_t q , - // sparsity pattern for the matrix R^T - const CppAD::vector< std::set >& rt , - // sparsoity pattern for the matrix S^T = f'(x)^T * R^T - CppAD::vector< std::set >& st , - const CppAD::vector& x ) - { - size_t nr_left = size_t( CppAD::Integer( x[0] ) ); - size_t n_middle = size_t( CppAD::Integer( x[1] ) ); - size_t nc_right = size_t( CppAD::Integer( x[2] ) ); - size_t nx = 3 + (nr_left + nc_right) * n_middle; -# ifndef NDEBUG - size_t ny = nr_left * nc_right; -# endif - // - assert( nx == st.size() ); - assert( ny == rt.size() ); - // - // initialize S^T as empty - for(size_t i = 0; i < nx; i++) - st[i].clear(); - - // sparsity for S(x)^T = f'(x)^T * R^T - size_t n_left = nr_left * n_middle; - for(size_t i = 0; i < nr_left; i++) - { for(size_t j = 0; j < nc_right; j++) - { // pack index for entry (i, j) in result - size_t i_result = i * nc_right + j; - st[i_result].clear(); - for(size_t ell = 0; ell < n_middle; ell++) - { // pack index for entry (i, ell) in left - size_t i_left = 3 + i * n_middle + ell; - // pack index for entry (ell, j) in right - size_t i_right = 3 + n_left + ell * nc_right + j; - // - st[i_left] = CppAD::set_union(st[i_left], rt[i_result]); - st[i_right] = CppAD::set_union(st[i_right], rt[i_result]); - } - } - } - return true; - } -/* %$$ -$subhead for_sparse_hes$$ -$srccode%cpp% */ - virtual bool for_sparse_hes( - // which components of x are variables for this call - const CppAD::vector& vx, - // sparsity pattern for the diagonal of R - const CppAD::vector& r , - // sparsity pattern for the vector S - const CppAD::vector& s , - // sparsity patternfor the Hessian H(x) - CppAD::vector< std::set >& h , - const CppAD::vector& x ) - { - size_t nr_left = size_t( CppAD::Integer( x[0] ) ); - size_t n_middle = size_t( CppAD::Integer( x[1] ) ); - size_t nc_right = size_t( CppAD::Integer( x[2] ) ); - size_t nx = 3 + (nr_left + nc_right) * n_middle; -# ifndef NDEBUG - size_t ny = nr_left * nc_right; -# endif - // - assert( vx.size() == nx ); - assert( r.size() == nx ); - assert( s.size() == ny ); - assert( h.size() == nx ); - // - // initilize h as empty - for(size_t i = 0; i < nx; i++) - h[i].clear(); - // - size_t n_left = nr_left * n_middle; - for(size_t i = 0; i < nr_left; i++) - { for(size_t j = 0; j < nc_right; j++) - { // pack index for entry (i, j) in result - size_t i_result = i * nc_right + j; - if( s[i_result] ) - { for(size_t ell = 0; ell < n_middle; ell++) - { // pack index for entry (i, ell) in left - size_t i_left = 3 + i * n_middle + ell; - // pack index for entry (ell, j) in right - size_t i_right = 3 + n_left + ell * nc_right + j; - if( r[i_left] & r[i_right] ) - { h[i_left].insert(i_right); - h[i_right].insert(i_left); - } - } - } - } - } - return true; - } -/* %$$ -$subhead rev_sparse_hes$$ -$srccode%cpp% */ - // reverse Hessian sparsity routine called by CppAD - virtual bool rev_sparse_hes( - // which components of x are variables for this call - const CppAD::vector& vx, - // sparsity pattern for S(x) = g'[f(x)] - const CppAD::vector& s , - // sparsity pattern for d/dx g[f(x)] = S(x) * f'(x) - CppAD::vector& t , - // number of columns in R, U(x), and V(x) - size_t q , - // sparsity pattern for R - const CppAD::vector< std::set >& r , - // sparsity pattern for U(x) = g^{(2)} [ f(x) ] * f'(x) * R - const CppAD::vector< std::set >& u , - // sparsity pattern for - // V(x) = f'(x)^T * U(x) + sum_{i=0}^{m-1} S_i(x) f_i^{(2)} (x) * R - CppAD::vector< std::set >& v , - // parameters as integers - const CppAD::vector& x ) - { - size_t nr_left = size_t( CppAD::Integer( x[0] ) ); - size_t n_middle = size_t( CppAD::Integer( x[1] ) ); - size_t nc_right = size_t( CppAD::Integer( x[2] ) ); - size_t nx = 3 + (nr_left + nc_right) * n_middle; -# ifndef NDEBUG - size_t ny = nr_left * nc_right; -# endif - // - assert( vx.size() == nx ); - assert( s.size() == ny ); - assert( t.size() == nx ); - assert( r.size() == nx ); - assert( v.size() == nx ); - // - // initilaize return sparsity patterns as false - for(size_t j = 0; j < nx; j++) - { t[j] = false; - v[j].clear(); - } - // - size_t n_left = nr_left * n_middle; - for(size_t i = 0; i < nr_left; i++) - { for(size_t j = 0; j < nc_right; j++) - { // pack index for entry (i, j) in result - size_t i_result = i * nc_right + j; - for(size_t ell = 0; ell < n_middle; ell++) - { // pack index for entry (i, ell) in left - size_t i_left = 3 + i * n_middle + ell; - // pack index for entry (ell, j) in right - size_t i_right = 3 + n_left + ell * nc_right + j; - // - // back propagate T(x) = S(x) * f'(x). - t[i_left] |= bool( s[i_result] ); - t[i_right] |= bool( s[i_result] ); - // - // V(x) = f'(x)^T * U(x) + sum_i S_i(x) * f_i''(x) * R - // U(x) = g''[ f(x) ] * f'(x) * R - // S_i(x) = g_i'[ f(x) ] - // - // back propagate f'(x)^T * U(x) - v[i_left] = CppAD::set_union(v[i_left], u[i_result] ); - v[i_right] = CppAD::set_union(v[i_right], u[i_result] ); - // - // back propagate S_i(x) * f_i''(x) * R - // (here is where we use vx to check for cross terms) - if( s[i_result] & vx[i_left] & vx[i_right] ) - { v[i_left] = CppAD::set_union(v[i_left], r[i_right] ); - v[i_right] = CppAD::set_union(v[i_right], r[i_left] ); - } - } - } - } - return true; - } -/* %$$ -$head End Class Definition$$ -$srccode%cpp% */ -}; // End of atomic_eigen_mat_mul class - -} // END_EMPTY_NAMESPACE -/* %$$ -$$ $comment end nospell$$ -$end -*/ - - -# endif diff --git a/ct_core/include/ct/external/cppad/example/eigen_plugin.hpp b/ct_core/include/ct/external/cppad/example/eigen_plugin.hpp deleted file mode 100644 index 84d6a5786..000000000 --- a/ct_core/include/ct/external/cppad/example/eigen_plugin.hpp +++ /dev/null @@ -1,28 +0,0 @@ -// $Id: eigen_plugin.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_EIGEN_PLUGIN_HPP -# define CPPAD_EIGEN_PLUGIN_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/*$ -$begin eigen_plugin.hpp$$ -$spell - eigen_plugin.hpp - typedef -$$ - -$section Source Code for eigen_plugin.hpp$$ -$codep */ -// Declaration needed so an Eigen vector is a simple vector -typedef Scalar value_type; -/* $$ -$end -*/ -# endif diff --git a/ct_core/include/ct/external/cppad/example/mat_mul.hpp b/ct_core/include/ct/external/cppad/example/mat_mul.hpp deleted file mode 100644 index e6f50cb59..000000000 --- a/ct_core/include/ct/external/cppad/example/mat_mul.hpp +++ /dev/null @@ -1,678 +0,0 @@ -// $Id$ -# ifndef CPPAD_EXAMPLE_MAT_MUL_HPP -# define CPPAD_EXAMPLE_MAT_MUL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin atomic_mat_mul.hpp$$ -$spell - Taylor - ty - px - CppAD - jac - hes - nr - nc -$$ - -$section Matrix Multiply as an Atomic Operation$$ - -$head See Also$$ -$cref atomic_eigen_mat_mul.hpp$$ - -$head Matrix Dimensions$$ -This example puts the matrix dimensions in the atomic function arguments, -instead of the $cref/constructor/atomic_ctor/$$, so that they can -be different for different calls to the atomic function. -These dimensions are: -$table -$icode nr_left$$ $cnext number of rows in the left matrix $rend -$icode n_middle$$ $cnext rows in the left matrix and columns in right $rend -$icode nc_right$$ $cnext number of columns in the right matrix -$tend - -$head Start Class Definition$$ -$srccode%cpp% */ -# include -namespace { // Begin empty namespace -using CppAD::vector; -// -using CppAD::set_union; -// -// matrix result = left * right -class atomic_mat_mul : public CppAD::atomic_base { -/* %$$ -$head Constructor$$ -$srccode%cpp% */ -public: - // --------------------------------------------------------------------- - // constructor - atomic_mat_mul(void) : CppAD::atomic_base("mat_mul") - { } -private: -/* %$$ -$head Left Operand Element Index$$ -Index in the Taylor coefficient matrix $icode tx$$ of a left matrix element. -$srccode%cpp% */ - size_t left( - size_t i , // left matrix row index - size_t j , // left matrix column index - size_t k , // Taylor coeffocient order - size_t nk , // number of Taylor coefficients in tx - size_t nr_left , // rows in left matrix - size_t n_middle , // rows in left and columns in right - size_t nc_right ) // columns in right matrix - { assert( i < nr_left ); - assert( j < n_middle ); - return (3 + i * n_middle + j) * nk + k; - } -/* %$$ -$head Right Operand Element Index$$ -Index in the Taylor coefficient matrix $icode tx$$ of a right matrix element. -$srccode%cpp% */ - size_t right( - size_t i , // right matrix row index - size_t j , // right matrix column index - size_t k , // Taylor coeffocient order - size_t nk , // number of Taylor coefficients in tx - size_t nr_left , // rows in left matrix - size_t n_middle , // rows in left and columns in right - size_t nc_right ) // columns in right matrix - { assert( i < n_middle ); - assert( j < nc_right ); - size_t offset = 3 + nr_left * n_middle; - return (offset + i * nc_right + j) * nk + k; - } -/* %$$ -$head Result Element Index$$ -Index in the Taylor coefficient matrix $icode ty$$ of a result matrix element. -$srccode%cpp% */ - size_t result( - size_t i , // result matrix row index - size_t j , // result matrix column index - size_t k , // Taylor coeffocient order - size_t nk , // number of Taylor coefficients in ty - size_t nr_left , // rows in left matrix - size_t n_middle , // rows in left and columns in right - size_t nc_right ) // columns in right matrix - { assert( i < nr_left ); - assert( j < nc_right ); - return (i * nc_right + j) * nk + k; - } -/* %$$ -$head Forward Matrix Multiply$$ -Forward mode multiply Taylor coefficients in $icode tx$$ and sum into -$icode ty$$ (for one pair of left and right orders) -$srccode%cpp% */ - void forward_multiply( - size_t k_left , // order for left coefficients - size_t k_right , // order for right coefficients - const vector& tx , // domain space Taylor coefficients - vector& ty , // range space Taylor coefficients - size_t nr_left , // rows in left matrix - size_t n_middle , // rows in left and columns in right - size_t nc_right ) // columns in right matrix - { - size_t nx = 3 + (nr_left + nc_right) * n_middle; - size_t nk = tx.size() / nx; -# ifndef NDEBUG - size_t ny = nr_left * nc_right; - assert( nk == ty.size() / ny ); -# endif - // - size_t k_result = k_left + k_right; - assert( k_result < nk ); - // - for(size_t i = 0; i < nr_left; i++) - { for(size_t j = 0; j < nc_right; j++) - { double sum = 0.0; - for(size_t ell = 0; ell < n_middle; ell++) - { size_t i_left = left( - i, ell, k_left, nk, nr_left, n_middle, nc_right - ); - size_t i_right = right( - ell, j, k_right, nk, nr_left, n_middle, nc_right - ); - sum += tx[i_left] * tx[i_right]; - } - size_t i_result = result( - i, j, k_result, nk, nr_left, n_middle, nc_right - ); - ty[i_result] += sum; - } - } - } -/* %$$ -$head Reverse Matrix Multiply$$ -Reverse mode partials of Taylor coefficients and sum into $icode px$$ -(for one pair of left and right orders) -$srccode%cpp% */ - void reverse_multiply( - size_t k_left , // order for left coefficients - size_t k_right , // order for right coefficients - const vector& tx , // domain space Taylor coefficients - const vector& ty , // range space Taylor coefficients - vector& px , // partials w.r.t. tx - const vector& py , // partials w.r.t. ty - size_t nr_left , // rows in left matrix - size_t n_middle , // rows in left and columns in right - size_t nc_right ) // columns in right matrix - { - size_t nx = 3 + (nr_left + nc_right) * n_middle; - size_t nk = tx.size() / nx; -# ifndef NDEBUG - size_t ny = nr_left * nc_right; - assert( nk == ty.size() / ny ); -# endif - assert( tx.size() == px.size() ); - assert( ty.size() == py.size() ); - // - size_t k_result = k_left + k_right; - assert( k_result < nk ); - // - for(size_t i = 0; i < nr_left; i++) - { for(size_t j = 0; j < nc_right; j++) - { size_t i_result = result( - i, j, k_result, nk, nr_left, n_middle, nc_right - ); - for(size_t ell = 0; ell < n_middle; ell++) - { size_t i_left = left( - i, ell, k_left, nk, nr_left, n_middle, nc_right - ); - size_t i_right = right( - ell, j, k_right, nk, nr_left, n_middle, nc_right - ); - // sum += tx[i_left] * tx[i_right]; - px[i_left] += tx[i_right] * py[i_result]; - px[i_right] += tx[i_left] * py[i_result]; - } - } - } - return; - } -/* %$$ -$head forward$$ -Routine called by CppAD during $cref Forward$$ mode. -$srccode%cpp% */ - virtual bool forward( - size_t q , - size_t p , - const vector& vx , - vector& vy , - const vector& tx , - vector& ty - ) - { size_t n_order = p + 1; - size_t nr_left = size_t( tx[ 0 * n_order + 0 ] ); - size_t n_middle = size_t( tx[ 1 * n_order + 0 ] ); - size_t nc_right = size_t( tx[ 2 * n_order + 0 ] ); -# ifndef NDEBUG - size_t nx = 3 + (nr_left + nc_right) * n_middle; - size_t ny = nr_left * nc_right; -# endif - assert( vx.size() == 0 || nx == vx.size() ); - assert( vx.size() == 0 || ny == vy.size() ); - assert( nx * n_order == tx.size() ); - assert( ny * n_order == ty.size() ); - size_t i, j, ell; - - // check if we are computing vy information - if( vx.size() > 0 ) - { size_t nk = 1; - size_t k = 0; - for(i = 0; i < nr_left; i++) - { for(j = 0; j < nc_right; j++) - { bool var = false; - for(ell = 0; ell < n_middle; ell++) - { size_t i_left = left( - i, ell, k, nk, nr_left, n_middle, nc_right - ); - size_t i_right = right( - ell, j, k, nk, nr_left, n_middle, nc_right - ); - bool nz_left = vx[i_left] |(tx[i_left] != 0.); - bool nz_right = vx[i_right]|(tx[i_right] != 0.); - // if not multiplying by the constant zero - if( nz_left & nz_right ) - var |= bool(vx[i_left]) | bool(vx[i_right]); - } - size_t i_result = result( - i, j, k, nk, nr_left, n_middle, nc_right - ); - vy[i_result] = var; - } - } - } - - // initialize result as zero - size_t k; - for(i = 0; i < nr_left; i++) - { for(j = 0; j < nc_right; j++) - { for(k = q; k <= p; k++) - { size_t i_result = result( - i, j, k, n_order, nr_left, n_middle, nc_right - ); - ty[i_result] = 0.0; - } - } - } - for(k = q; k <= p; k++) - { // sum the produces that result in order k - for(ell = 0; ell <= k; ell++) - forward_multiply( - ell, k - ell, tx, ty, nr_left, n_middle, nc_right - ); - } - - // all orders are implented, so always return true - return true; - } -/* %$$ -$head reverse$$ -Routine called by CppAD during $cref Reverse$$ mode. -$srccode%cpp% */ - virtual bool reverse( - size_t p , - const vector& tx , - const vector& ty , - vector& px , - const vector& py - ) - { size_t n_order = p + 1; - size_t nr_left = size_t( tx[ 0 * n_order + 0 ] ); - size_t n_middle = size_t( tx[ 1 * n_order + 0 ] ); - size_t nc_right = size_t( tx[ 2 * n_order + 0 ] ); -# ifndef NDEBUG - size_t nx = 3 + (nr_left + nc_right) * n_middle; - size_t ny = nr_left * nc_right; -# endif - assert( nx * n_order == tx.size() ); - assert( ny * n_order == ty.size() ); - assert( px.size() == tx.size() ); - assert( py.size() == ty.size() ); - - // initialize summation - for(size_t i = 0; i < px.size(); i++) - px[i] = 0.0; - - // number of orders to differentiate - size_t k = n_order; - while(k--) - { // differentiate the produces that result in order k - for(size_t ell = 0; ell <= k; ell++) - reverse_multiply( - ell, k - ell, tx, ty, px, py, nr_left, n_middle, nc_right - ); - } - - // all orders are implented, so always return true - return true; - } -/* %$$ -$head for_sparse_jac$$ -Routines called by CppAD during $cref ForSparseJac$$. -$srccode%cpp% */ - // boolean sparsity patterns - virtual bool for_sparse_jac( - size_t q , - const vector& r , - vector& s , - const vector& x ) - { - size_t nr_left = size_t( CppAD::Integer( x[0] ) ); - size_t n_middle = size_t( CppAD::Integer( x[1] ) ); - size_t nc_right = size_t( CppAD::Integer( x[2] ) ); -# ifndef NDEBUG - size_t nx = 3 + (nr_left + nc_right) * n_middle; - size_t ny = nr_left * nc_right; -# endif - assert( nx == x.size() ); - assert( nx * q == r.size() ); - assert( ny * q == s.size() ); - size_t p; - - // sparsity for S(x) = f'(x) * R - size_t nk = 1; - size_t k = 0; - for(size_t i = 0; i < nr_left; i++) - { for(size_t j = 0; j < nc_right; j++) - { size_t i_result = result( - i, j, k, nk, nr_left, n_middle, nc_right - ); - for(p = 0; p < q; p++) - s[i_result * q + p] = false; - for(size_t ell = 0; ell < n_middle; ell++) - { size_t i_left = left( - i, ell, k, nk, nr_left, n_middle, nc_right - ); - size_t i_right = right( - ell, j, k, nk, nr_left, n_middle, nc_right - ); - for(p = 0; p < q; p++) - { // cast avoids Microsoft warning (should not be needed) - s[i_result * q + p] |= bool( r[i_left * q + p ] ); - s[i_result * q + p] |= bool( r[i_right * q + p ] ); - } - } - } - } - return true; - } - // set sparsity patterns - virtual bool for_sparse_jac( - size_t q , - const vector< std::set >& r , - vector< std::set >& s , - const vector& x ) - { - size_t nr_left = size_t( CppAD::Integer( x[0] ) ); - size_t n_middle = size_t( CppAD::Integer( x[1] ) ); - size_t nc_right = size_t( CppAD::Integer( x[2] ) ); -# ifndef NDEBUG - size_t nx = 3 + (nr_left + nc_right) * n_middle; - size_t ny = nr_left * nc_right; -# endif - assert( nx == x.size() ); - assert( nx == r.size() ); - assert( ny == s.size() ); - - // sparsity for S(x) = f'(x) * R - size_t nk = 1; - size_t k = 0; - for(size_t i = 0; i < nr_left; i++) - { for(size_t j = 0; j < nc_right; j++) - { size_t i_result = result( - i, j, k, nk, nr_left, n_middle, nc_right - ); - s[i_result].clear(); - for(size_t ell = 0; ell < n_middle; ell++) - { size_t i_left = left( - i, ell, k, nk, nr_left, n_middle, nc_right - ); - size_t i_right = right( - ell, j, k, nk, nr_left, n_middle, nc_right - ); - // - s[i_result] = set_union(s[i_result], r[i_left] ); - s[i_result] = set_union(s[i_result], r[i_right] ); - } - } - } - return true; - } -/* %$$ -$head rev_sparse_jac$$ -Routines called by CppAD during $cref RevSparseJac$$. -$srccode%cpp% */ - // boolean sparsity patterns - virtual bool rev_sparse_jac( - size_t q , - const vector& rt , - vector& st , - const vector& x ) - { - size_t nr_left = size_t( CppAD::Integer( x[0] ) ); - size_t n_middle = size_t( CppAD::Integer( x[1] ) ); - size_t nc_right = size_t( CppAD::Integer( x[2] ) ); - size_t nx = 3 + (nr_left + nc_right) * n_middle; -# ifndef NDEBUG - size_t ny = nr_left * nc_right; -# endif - assert( nx == x.size() ); - assert( nx * q == st.size() ); - assert( ny * q == rt.size() ); - size_t i, j, p; - - // initialize - for(i = 0; i < nx; i++) - { for(p = 0; p < q; p++) - st[ i * q + p ] = false; - } - - // sparsity for S(x)^T = f'(x)^T * R^T - size_t nk = 1; - size_t k = 0; - for(i = 0; i < nr_left; i++) - { for(j = 0; j < nc_right; j++) - { size_t i_result = result( - i, j, k, nk, nr_left, n_middle, nc_right - ); - for(size_t ell = 0; ell < n_middle; ell++) - { size_t i_left = left( - i, ell, k, nk, nr_left, n_middle, nc_right - ); - size_t i_right = right( - ell, j, k, nk, nr_left, n_middle, nc_right - ); - for(p = 0; p < q; p++) - { st[i_left * q + p] |= bool( rt[i_result * q + p] ); - st[i_right* q + p] |= bool( rt[i_result * q + p] ); - } - } - } - } - return true; - } - // set sparsity patterns - virtual bool rev_sparse_jac( - size_t q , - const vector< std::set >& rt , - vector< std::set >& st , - const vector& x ) - { - size_t nr_left = size_t( CppAD::Integer( x[0] ) ); - size_t n_middle = size_t( CppAD::Integer( x[1] ) ); - size_t nc_right = size_t( CppAD::Integer( x[2] ) ); - size_t nx = 3 + (nr_left + nc_right) * n_middle; -# ifndef NDEBUG - size_t ny = nr_left * nc_right; -# endif - assert( nx == x.size() ); - assert( nx == st.size() ); - assert( ny == rt.size() ); - size_t i, j; - - // initialize - for(i = 0; i < nx; i++) - st[i].clear(); - - // sparsity for S(x)^T = f'(x)^T * R^T - size_t nk = 1; - size_t k = 0; - for(i = 0; i < nr_left; i++) - { for(j = 0; j < nc_right; j++) - { size_t i_result = result( - i, j, k, nk, nr_left, n_middle, nc_right - ); - for(size_t ell = 0; ell < n_middle; ell++) - { size_t i_left = left( - i, ell, k, nk, nr_left, n_middle, nc_right - ); - size_t i_right = right( - ell, j, k, nk, nr_left, n_middle, nc_right - ); - // - st[i_left] = set_union(st[i_left], rt[i_result]); - st[i_right] = set_union(st[i_right], rt[i_result]); - } - } - } - return true; - } -/* %$$ -$head rev_sparse_hes$$ -Routines called by $cref RevSparseHes$$. -$srccode%cpp% */ - // set sparsity patterns - virtual bool rev_sparse_hes( - const vector& vx, - const vector& s , - vector& t , - size_t q , - const vector< std::set >& r , - const vector< std::set >& u , - vector< std::set >& v , - const vector& x ) - { - size_t nr_left = size_t( CppAD::Integer( x[0] ) ); - size_t n_middle = size_t( CppAD::Integer( x[1] ) ); - size_t nc_right = size_t( CppAD::Integer( x[2] ) ); - size_t nx = 3 + (nr_left + nc_right) * n_middle; -# ifndef NDEBUG - size_t ny = nr_left * nc_right; -# endif - assert( x.size() == nx ); - assert( vx.size() == nx ); - assert( t.size() == nx ); - assert( r.size() == nx ); - assert( v.size() == nx ); - assert( s.size() == ny ); - assert( u.size() == ny ); - // - size_t i, j; - // - // initilaize sparsity patterns as false - for(j = 0; j < nx; j++) - { t[j] = false; - v[j].clear(); - } - size_t nk = 1; - size_t k = 0; - for(i = 0; i < nr_left; i++) - { for(j = 0; j < nc_right; j++) - { size_t i_result = result( - i, j, k, nk, nr_left, n_middle, nc_right - ); - for(size_t ell = 0; ell < n_middle; ell++) - { size_t i_left = left( - i, ell, k, nk, nr_left, n_middle, nc_right - ); - size_t i_right = right( - ell, j, k, nk, nr_left, n_middle, nc_right - ); - // - // Compute sparsity for T(x) = S(x) * f'(x). - // We need not use vx with f'(x) back propagation. - t[i_left] |= bool( s[i_result] ); - t[i_right] |= bool( s[i_result] ); - - // V(x) = f'(x)^T * U(x) + S(x) * f''(x) * R - // U(x) = g''(y) * f'(x) * R - // S(x) = g'(y) - - // back propagate f'(x)^T * U(x) - // (no need to use vx with f'(x) propogation) - v[i_left] = set_union(v[i_left], u[i_result] ); - v[i_right] = set_union(v[i_right], u[i_result] ); - - // back propagate S(x) * f''(x) * R - // (here is where we must check for cross terms) - if( s[i_result] & vx[i_left] & vx[i_right] ) - { v[i_left] = set_union(v[i_left], r[i_right] ); - v[i_right] = set_union(v[i_right], r[i_left] ); - } - } - } - } - return true; - } - // bool sparsity - virtual bool rev_sparse_hes( - const vector& vx, - const vector& s , - vector& t , - size_t q , - const vector& r , - const vector& u , - vector& v , - const vector& x ) - { - size_t nr_left = size_t( CppAD::Integer( x[0] ) ); - size_t n_middle = size_t( CppAD::Integer( x[1] ) ); - size_t nc_right = size_t( CppAD::Integer( x[2] ) ); - size_t nx = 3 + (nr_left + nc_right) * n_middle; -# ifndef NDEBUG - size_t ny = nr_left * nc_right; -# endif - assert( x.size() == nx ); - assert( vx.size() == nx ); - assert( t.size() == nx ); - assert( r.size() == nx * q ); - assert( v.size() == nx * q ); - assert( s.size() == ny ); - assert( u.size() == ny * q ); - size_t i, j, p; - // - // initilaize sparsity patterns as false - for(j = 0; j < nx; j++) - { t[j] = false; - for(p = 0; p < q; p++) - v[j * q + p] = false; - } - size_t nk = 1; - size_t k = 0; - for(i = 0; i < nr_left; i++) - { for(j = 0; j < nc_right; j++) - { size_t i_result = result( - i, j, k, nk, nr_left, n_middle, nc_right - ); - for(size_t ell = 0; ell < n_middle; ell++) - { size_t i_left = left( - i, ell, k, nk, nr_left, n_middle, nc_right - ); - size_t i_right = right( - ell, j, k, nk, nr_left, n_middle, nc_right - ); - // - // Compute sparsity for T(x) = S(x) * f'(x). - // We so not need to use vx with f'(x) propagation. - t[i_left] |= bool( s[i_result] ); - t[i_right] |= bool( s[i_result] ); - - // V(x) = f'(x)^T * U(x) + S(x) * f''(x) * R - // U(x) = g''(y) * f'(x) * R - // S(x) = g'(y) - - // back propagate f'(x)^T * U(x) - // (no need to use vx with f'(x) propogation) - for(p = 0; p < q; p++) - { v[ i_left * q + p] |= bool( u[ i_result * q + p] ); - v[ i_right * q + p] |= bool( u[ i_result * q + p] ); - } - - // back propagate S(x) * f''(x) * R - // (here is where we must check for cross terms) - if( s[i_result] & vx[i_left] & vx[i_right] ) - { for(p = 0; p < q; p++) - { v[i_left * q + p] |= bool( r[i_right * q + p] ); - v[i_right * q + p] |= bool( r[i_left * q + p] ); - } - } - } - } - } - return true; - } -/* %$$ -$head End Class Definition$$ -$srccode%cpp% */ -}; // End of mat_mul class -} // End empty namespace -/* %$$ -$comment end nospell$$ -$end -*/ - - -# endif diff --git a/ct_core/include/ct/external/cppad/example/matrix_mul.hpp b/ct_core/include/ct/external/cppad/example/matrix_mul.hpp deleted file mode 100644 index f4a684146..000000000 --- a/ct_core/include/ct/external/cppad/example/matrix_mul.hpp +++ /dev/null @@ -1,529 +0,0 @@ -// $Id: matrix_mul.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_MATRIX_MUL_HPP -# define CPPAD_MATRIX_MUL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin atomic_matrix_mul.hpp$$ -$spell -$$ - -$section Matrix Multiply as an Atomic Operation$$ - -$nospell - -$head Start Class Definition$$ -$codep */ -# include -namespace { // Begin empty namespace -using CppAD::vector; -// -void my_union( - std::set& result , - const std::set& left , - const std::set& right ) -{ std::set temp; - std::set_union( - left.begin() , - left.end() , - right.begin() , - right.end() , - std::inserter(temp, temp.begin()) - ); - result.swap(temp); -} -// -// matrix result = left * right -class matrix_mul : public CppAD::atomic_base { -/* $$ -$head Constructor$$ -$codep */ - private: - // number of rows in left operand and in the result - const size_t nr_result_; - // number of columns in left operand and rows in right operand - const size_t n_middle_; - // number of columns in right operand and in the result - const size_t nc_result_; - // dimension of the domain space - const size_t n_; - // dimension of the range space -# ifndef NDEBUG - const size_t m_; -# endif - public: - // --------------------------------------------------------------------- - // constructor - matrix_mul(size_t nr_result, size_t n_middle, size_t nc_result) - : CppAD::atomic_base("matrix_mul"), - nr_result_(nr_result) , - n_middle_(n_middle) , - nc_result_(nc_result) , - n_( nr_result * n_middle + n_middle * nc_result ) -# ifndef NDEBUG - , m_( n_middle * nc_result ) -# endif - { } - private: -/* $$ -$head Left Operand Element Index$$ -$codep */ - // left matrix element index in the taylor coefficient vector tx. - size_t left( - size_t i , // left matrix row index - size_t j , // left matrix column index - size_t k , // Taylor coeffocient order - size_t nk ) // number of Taylor coefficients in tx - { assert( i < nr_result_ ); - assert( j < n_middle_ ); - return (i * n_middle_ + j) * nk + k; - } -/* $$ -$head Right Operand Element Index$$ -$codep */ - // right matrix element index in the taylor coefficient vector tx. - size_t right( - size_t i , // right matrix row index - size_t j , // right matrix column index - size_t k , // Taylor coeffocient order - size_t nk ) // number of Taylor coefficients in tx - { assert( i < n_middle_ ); - assert( j < nc_result_ ); - size_t offset = nr_result_ * n_middle_; - return (offset + i * nc_result_ + j) * nk + k; - } -/* $$ -$head Result Element Index$$ -$codep */ - // result matrix element index in the taylor coefficient vector ty. - size_t result( - size_t i , // result matrix row index - size_t j , // result matrix column index - size_t k , // Taylor coeffocient order - size_t nk ) // number of Taylor coefficients in ty - { assert( i < nr_result_ ); - assert( j < nc_result_ ); - return (i * nc_result_ + j) * nk + k; - } -/* $$ -$head Forward Matrix Multipliy$$ -$codep */ - // Forward mode multiply Taylor coefficients in tx and sum into ty - // (for one pair of left and right orders) - void forward_multiply( - size_t k_left , // order for left coefficients - size_t k_right , // order for right coefficients - const vector& tx , // domain space Taylor coefficients - vector& ty ) // range space Taylor coefficients - { size_t nk = tx.size() / n_; - assert( nk == ty.size() / m_ ); - // - size_t k_result = k_left + k_right; - assert( k_result < nk ); - // - for(size_t i = 0; i < nr_result_; i++) - { for(size_t j = 0; j < nc_result_; j++) - { double sum = 0.0; - for(size_t ell = 0; ell < n_middle_; ell++) - { size_t i_left = left(i, ell, k_left, nk); - size_t i_right = right(ell, j, k_right, nk); - sum += tx[i_left] * tx[i_right]; - } - size_t i_result = result(i, j, k_result, nk); - ty[i_result] += sum; - } - } - } -/* $$ -$head Reverse Matrix Multipliy$$ -$codep */ - // Reverse mode partials of Taylor coefficients and sum into px - // (for one pair of left and right orders) - void reverse_multiply( - size_t k_left , // order for left coefficients - size_t k_right , // order for right coefficients - const vector& tx , // domain space Taylor coefficients - const vector& ty , // range space Taylor coefficients - vector& px , // partials w.r.t. tx - const vector& py ) // partials w.r.t. ty - { size_t nk = tx.size() / n_; - assert( nk == ty.size() / m_ ); - assert( tx.size() == px.size() ); - assert( ty.size() == py.size() ); - // - size_t k_result = k_left + k_right; - assert( k_result < nk ); - // - for(size_t i = 0; i < nr_result_; i++) - { for(size_t j = 0; j < nc_result_; j++) - { size_t i_result = result(i, j, k_result, nk); - for(size_t ell = 0; ell < n_middle_; ell++) - { size_t i_left = left(i, ell, k_left, nk); - size_t i_right = right(ell, j, k_right, nk); - // sum += tx[i_left] * tx[i_right]; - px[i_left] += tx[i_right] * py[i_result]; - px[i_right] += tx[i_left] * py[i_result]; - } - } - } - return; - } -/* $$ -$head forward$$ -$codep */ - // forward mode routine called by CppAD - bool forward( - size_t q , - size_t p , - const vector& vx , - vector& vy , - const vector& tx , - vector& ty - ) - { size_t p1 = p + 1; - assert( vx.size() == 0 || n_ == vx.size() ); - assert( vx.size() == 0 || m_ == vy.size() ); - assert( n_ * p1 == tx.size() ); - assert( m_ * p1 == ty.size() ); - size_t i, j, ell; - - // check if we are computing vy information - if( vx.size() > 0 ) - { size_t nk = 1; - size_t k = 0; - for(i = 0; i < nr_result_; i++) - { for(j = 0; j < nc_result_; j++) - { bool var = false; - for(ell = 0; ell < n_middle_; ell++) - { size_t i_left = left(i, ell, k, nk); - size_t i_right = right(ell, j, k, nk); - bool nz_left = vx[i_left] |(tx[i_left] != 0.); - bool nz_right = vx[i_right]|(tx[i_right] != 0.); - // if not multiplying by the constant zero - if( nz_left & nz_right ) - var |= bool(vx[i_left]) | bool(vx[i_right]); - } - size_t i_result = result(i, j, k, nk); - vy[i_result] = var; - } - } - } - - // initialize result as zero - size_t k; - for(i = 0; i < nr_result_; i++) - { for(j = 0; j < nc_result_; j++) - { for(k = q; k <= p; k++) - ty[ result(i, j, k, p1) ] = 0.0; - } - } - for(k = q; k <= p; k++) - { // sum the produces that result in order k - for(ell = 0; ell <= k; ell++) - forward_multiply(ell, k - ell, tx, ty); - } - - // all orders are implented, so always return true - return true; - } -/* $$ -$head reverse$$ -$codep */ - // reverse mode routine called by CppAD - virtual bool reverse( - size_t p , - const vector& tx , - const vector& ty , - vector& px , - const vector& py - ) - { size_t p1 = p + 1; - assert( n_ * p1 == tx.size() ); - assert( m_ * p1 == ty.size() ); - assert( px.size() == tx.size() ); - assert( py.size() == ty.size() ); - - // initialize summation - for(size_t i = 0; i < px.size(); i++) - px[i] = 0.0; - - // number of orders to differentiate - size_t k = p1; - while(k--) - { // differentiate the produces that result in order k - for(size_t ell = 0; ell <= k; ell++) - reverse_multiply(ell, k - ell, tx, ty, px, py); - } - - // all orders are implented, so always return true - return true; - } -/* $$ -$head for_sparse_jac$$ -$codep */ - // forward Jacobian sparsity routine called by CppAD - virtual bool for_sparse_jac( - size_t q , - const vector& r , - vector& s ) - { assert( n_ * q == r.size() ); - assert( m_ * q == s.size() ); - size_t p; - - // sparsity for S(x) = f'(x) * R - size_t nk = 1; - size_t k = 0; - for(size_t i = 0; i < nr_result_; i++) - { for(size_t j = 0; j < nc_result_; j++) - { size_t i_result = result(i, j, k, nk); - for(p = 0; p < q; p++) - s[i_result * q + p] = false; - for(size_t ell = 0; ell < n_middle_; ell++) - { size_t i_left = left(i, ell, k, nk); - size_t i_right = right(ell, j, k, nk); - for(p = 0; p < q; p++) - { // cast avoids Microsoft warning (should not be needed) - s[i_result * q + p] |= bool( r[i_left * q + p ] ); - s[i_result * q + p] |= bool( r[i_right * q + p ] ); - } - } - } - } - return true; - } - virtual bool for_sparse_jac( - size_t q , - const vector< std::set >& r , - vector< std::set >& s ) - { assert( n_ == r.size() ); - assert( m_ == s.size() ); - - // sparsity for S(x) = f'(x) * R - size_t nk = 1; - size_t k = 0; - for(size_t i = 0; i < nr_result_; i++) - { for(size_t j = 0; j < nc_result_; j++) - { size_t i_result = result(i, j, k, nk); - s[i_result].clear(); - for(size_t ell = 0; ell < n_middle_; ell++) - { size_t i_left = left(i, ell, k, nk); - size_t i_right = right(ell, j, k, nk); - // - my_union( s[i_result], s[i_result], r[i_left] ); - my_union( s[i_result], s[i_result], r[i_right] ); - } - } - } - return true; - } -/* $$ -$head rev_sparse_jac$$ -$codep */ - // reverse Jacobian sparsity routine called by CppAD - virtual bool rev_sparse_jac( - size_t q , - const vector& rt , - vector& st ) - { assert( n_ * q == st.size() ); - assert( m_ * q == rt.size() ); - size_t i, j, p; - - // initialize - for(i = 0; i < n_; i++) - { for(p = 0; p < q; p++) - st[ i * q + p ] = false; - } - - // sparsity for S(x)^T = f'(x)^T * R^T - size_t nk = 1; - size_t k = 0; - for(i = 0; i < nr_result_; i++) - { for(j = 0; j < nc_result_; j++) - { size_t i_result = result(i, j, k, nk); - for(size_t ell = 0; ell < n_middle_; ell++) - { size_t i_left = left(i, ell, k, nk); - size_t i_right = right(ell, j, k, nk); - for(p = 0; p < q; p++) - { st[i_left * q + p] |= bool( rt[i_result * q + p] ); - st[i_right* q + p] |= bool( rt[i_result * q + p] ); - } - } - } - } - return true; - } - virtual bool rev_sparse_jac( - size_t q , - const vector< std::set >& rt , - vector< std::set >& st ) - { assert( n_ == st.size() ); - assert( m_ == rt.size() ); - size_t i, j; - - // initialize - for(i = 0; i < n_; i++) - st[i].clear(); - - // sparsity for S(x)^T = f'(x)^T * R^T - size_t nk = 1; - size_t k = 0; - for(i = 0; i < nr_result_; i++) - { for(j = 0; j < nc_result_; j++) - { size_t i_result = result(i, j, k, nk); - for(size_t ell = 0; ell < n_middle_; ell++) - { size_t i_left = left(i, ell, k, nk); - size_t i_right = right(ell, j, k, nk); - // - my_union(st[i_left], st[i_left], rt[i_result]); - my_union(st[i_right], st[i_right], rt[i_result]); - } - } - } - return true; - } -/* $$ -$head rev_sparse_hes$$ -$codep */ - // reverse Hessian sparsity routine called by CppAD - virtual bool rev_sparse_hes( - const vector& vx, - const vector& s , - vector& t , - size_t q , - const vector< std::set >& r , - const vector< std::set >& u , - vector< std::set >& v ) - { size_t n = vx.size(); - assert( t.size() == n ); - assert( r.size() == n ); - assert( v.size() == n ); -# ifndef NDEBUG - size_t m = s.size(); - assert( u.size() == m ); -# endif - size_t i, j; - // - // initilaize sparsity patterns as false - for(j = 0; j < n; j++) - { t[j] = false; - v[j].clear(); - } - size_t nk = 1; - size_t k = 0; - for(i = 0; i < nr_result_; i++) - { for(j = 0; j < nc_result_; j++) - { size_t i_result = result(i, j, k, nk); - for(size_t ell = 0; ell < n_middle_; ell++) - { size_t i_left = left(i, ell, k, nk); - size_t i_right = right(ell, j, k, nk); - // - // Compute sparsity for T(x) = S(x) * f'(x). - // We need not use vx with f'(x) back propagation. - t[i_left] |= bool( s[i_result] ); - t[i_right] |= bool( s[i_result] ); - - // V(x) = f'(x)^T * U(x) + S(x) * f''(x) * R - // U(x) = g''(y) * f'(x) * R - // S(x) = g'(y) - - // back propagate f'(x)^T * U(x) - // (no need to use vx with f'(x) propogation) - my_union(v[i_left], v[i_left], u[i_result] ); - my_union(v[i_right], v[i_right], u[i_result] ); - - // back propagate S(x) * f''(x) * R - // (here is where we must check for cross terms) - if( s[i_result] & vx[i_left] & vx[i_right] ) - { my_union(v[i_left], v[i_left], r[i_right] ); - my_union(v[i_right], v[i_right], r[i_left] ); - } - } - } - } - return true; - } - virtual bool rev_sparse_hes( - const vector& vx, - const vector& s , - vector& t , - size_t q , - const vector& r , - const vector& u , - vector& v ) - { size_t n = vx.size(); - assert( t.size() == n ); - assert( r.size() == n * q ); - assert( v.size() == n * q ); -# ifndef NDEBUG - size_t m = s.size(); - assert( u.size() == m * q ); -# endif - size_t i, j, p; - // - // initilaize sparsity patterns as false - for(j = 0; j < n; j++) - { t[j] = false; - for(p = 0; p < q; p++) - v[j * q + p] = false; - } - size_t nk = 1; - size_t k = 0; - for(i = 0; i < nr_result_; i++) - { for(j = 0; j < nc_result_; j++) - { size_t i_result = result(i, j, k, nk); - for(size_t ell = 0; ell < n_middle_; ell++) - { size_t i_left = left(i, ell, k, nk); - size_t i_right = right(ell, j, k, nk); - // - // Compute sparsity for T(x) = S(x) * f'(x). - // We so not need to use vx with f'(x) propagation. - t[i_left] |= bool( s[i_result] ); - t[i_right] |= bool( s[i_result] ); - - // V(x) = f'(x)^T * U(x) + S(x) * f''(x) * R - // U(x) = g''(y) * f'(x) * R - // S(x) = g'(y) - - // back propagate f'(x)^T * U(x) - // (no need to use vx with f'(x) propogation) - for(p = 0; p < q; p++) - { v[ i_left * q + p] |= bool( u[ i_result * q + p] ); - v[ i_right * q + p] |= bool( u[ i_result * q + p] ); - } - - // back propagate S(x) * f''(x) * R - // (here is where we must check for cross terms) - if( s[i_result] & vx[i_left] & vx[i_right] ) - { for(p = 0; p < q; p++) - { v[i_left * q + p] |= bool( r[i_right * q + p] ); - v[i_right * q + p] |= bool( r[i_left * q + p] ); - } - } - } - } - } - return true; - } - -/* $$ -$head End Class Definition$$ -$codep */ -}; // End of matrix_mul class -} // End empty namespace -/* $$ -$$ $comment end nospell$$ -$end -*/ - - -# endif diff --git a/ct_core/include/ct/external/cppad/ipopt/solve.hpp b/ct_core/include/ct/external/cppad/ipopt/solve.hpp deleted file mode 100644 index dd6ca4912..000000000 --- a/ct_core/include/ct/external/cppad/ipopt/solve.hpp +++ /dev/null @@ -1,643 +0,0 @@ -// $Id: solve.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SOLVE_HPP -# define CPPAD_SOLVE_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin ipopt_solve$$ -$spell - Jacobian - Jacobians - retape - Bvector - bool - infeasibility - const - cpp - cppad - doesn't - ADvector - eval - fg - gl - gu - hpp - inf - ipopt - maxiter - naninf - nf - ng - nx - obj - optimizer - std - xi - xl - xu - zl - zu -$$ - -$section Use Ipopt to Solve a Nonlinear Programming Problem$$ - -$head Syntax$$ -$codei%# include -%$$ -$codei%ipopt::solve( - %options%, %xi%, %xl%, %xu%, %gl%, %gu%, %fg_eval%, %solution% -)%$$ - -$head Purpose$$ -The function $code ipopt::solve$$ solves nonlinear programming -problems of the form -$latex \[ -\begin{array}{rll} -{\rm minimize} & f (x) -\\ -{\rm subject \; to} & gl \leq g(x) \leq gu -\\ - & xl \leq x \leq xu -\end{array} -\] $$ -This is done using -$href% - http://www.coin-or.org/projects/Ipopt.xml% - Ipopt -%$$ -optimizer and CppAD for the derivative and sparsity calculations. - -$head Include File$$ -Currently, this routine -$cref/ipopt::solve/ipopt_solve/$$ is not included by the command -$codei% - # include -%$$ -(Doing so would require the ipopt library to link -the corresponding program (even if $code ipopt::solve$$) was not used.) -For this reason, -if you are using $code ipopt::solve$$ you should use -$codei% - # include -%$$ -which in turn will also include $code $$. - -$head Bvector$$ -The type $icode Bvector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code bool$$. - -$head Dvector$$ -The type $icode DVector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code double$$. - -$head options$$ -The argument $icode options$$ has prototype -$codei% - const std::string %options% -%$$ -It contains a list of options. -Each option, including the last option, -is terminated by the $code '\n'$$ character. -Each line consists of two or three tokens separated by one or more spaces. - -$subhead Retape$$ -You can set the retape flag with the following syntax: -$codei% - Retape %value% -%$$ -If the value is $code true$$, $code ipopt::solve$$ with retape the -$cref/operation sequence/glossary/Operation/Sequence/$$ for each -new value of $icode x$$. -If the value is $code false$$, $code ipopt::solve$$ -will tape the operation sequence at the value -of $icode xi$$ and use that sequence for the entire optimization process. -The default value is $code false$$. - -$subhead Sparse$$ -You can set the sparse Jacobian and Hessian flag with the following syntax: -$codei% - Sparse %value% %direction% -%$$ -If the value is $code true$$, $code ipopt::solve$$ will use a sparse -matrix representation for the computation of Jacobians and Hessians. -Otherwise, it will use a full matrix representation for -these calculations. -The default for $icode value$$ is $code false$$. -If sparse is true, retape must be false. -$pre - -$$ -It is unclear if $cref sparse_jacobian$$ would be faster user -forward or reverse mode so you are able to choose the direction. -If -$codei% - %value% == true && %direction% == forward -%$$ -the Jacobians will be calculated using $code SparseJacobianForward$$. -If -$codei% - %value% == true && %direction% == reverse -%$$ -the Jacobians will be calculated using $code SparseJacobianReverse$$. - -$subhead String$$ -You can set any Ipopt string option using a line with the following syntax: -$codei% - String %name% %value% -%$$ -Here $icode name$$ is any valid Ipopt string option -and $icode value$$ is its setting. - -$subhead Numeric$$ -You can set any Ipopt numeric option using a line with the following syntax: -$codei% - Numeric %name% %value% -%$$ -Here $icode name$$ is any valid Ipopt numeric option -and $icode value$$ is its setting. - -$subhead Integer$$ -You can set any Ipopt integer option using a line with the following syntax: -$codei% - Integer %name% %value% -%$$ -Here $icode name$$ is any valid Ipopt integer option -and $icode value$$ is its setting. - -$head xi$$ -The argument $icode xi$$ has prototype -$codei% - const %Vector%& %xi% -%$$ -and its size is equal to $icode nx$$. -It specifies the initial point where Ipopt starts the optimization process. - -$head xl$$ -The argument $icode xl$$ has prototype -$codei% - const %Vector%& %xl% -%$$ -and its size is equal to $icode nx$$. -It specifies the lower limits for the argument in the optimization problem. - -$head xu$$ -The argument $icode xu$$ has prototype -$codei% - const %Vector%& %xu% -%$$ -and its size is equal to $icode nx$$. -It specifies the upper limits for the argument in the optimization problem. - -$head gl$$ -The argument $icode gl$$ has prototype -$codei% - const %Vector%& %gl% -%$$ -and its size is equal to $icode ng$$. -It specifies the lower limits for the constraints in the optimization problem. - -$head gu$$ -The argument $icode gu$$ has prototype -$codei% - const %Vector%& %gu% -%$$ -and its size is equal to $icode ng$$. -It specifies the upper limits for the constraints in the optimization problem. - -$head fg_eval$$ -The argument $icode fg_eval$$ has prototype -$codei% - %FG_eval% %fg_eval% -%$$ -where the class $icode FG_eval$$ is unspecified except for the fact that -it supports the syntax -$codei% - %FG_eval%::ADvector - %fg_eval%(%fg%, %x%) -%$$ -The type $icode ADvector$$ -and the arguments to $icode fg$$, $icode x$$ have the following meaning: - -$subhead ADvector$$ -The type $icode%FG_eval%::ADvector%$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code AD$$. - -$subhead x$$ -The $icode fg_eval$$ argument $icode x$$ has prototype -$codei% - const %ADvector%& %x% -%$$ -where $icode%nx% = %x%.size()%$$. - -$subhead fg$$ -The $icode fg_eval$$ argument $icode fg$$ has prototype -$codei% - %ADvector%& %fg% -%$$ -where $codei%1 + %ng% = %fg%.size()%$$. -The input value of the elements of $icode fg$$ does not matter. -Upon return from $icode fg_eval$$, -$codei% - %fg%[0] =%$$ $latex f (x)$$ $codei% -%$$ -and for $latex i = 0, \ldots , ng-1$$, -$codei% - %fg%[1 + %i%] =%$$ $latex g_i (x)$$ - -$head solution$$ -The argument $icode solution$$ has prototype -$codei% - ipopt::solve_result<%Dvector%>& %solution% -%$$ -After the optimization process is completed, $icode solution$$ contains -the following information: - -$subhead status$$ -The $icode status$$ field of $icode solution$$ has prototype -$codei% - ipopt::solve_result<%Dvector%>::status_type %solution%.status -%$$ -It is the final Ipopt status for the optimizer. -Here is a list of the possible values for the status: - -$table -$icode status$$ $cnext Meaning -$rnext -not_defined $cnext -The optimizer did not return a final status for this problem. -$rnext -unknown $cnext -The status returned by the optimizer is not defined in the Ipopt -documentation for $code finalize_solution$$. -$rnext -success $cnext -Algorithm terminated successfully at a point satisfying the convergence -tolerances (see Ipopt options). -$rnext -maxiter_exceeded $cnext -The maximum number of iterations was exceeded (see Ipopt options). -$rnext -stop_at_tiny_step $cnext -Algorithm terminated because progress was very slow. -$rnext -stop_at_acceptable_point $cnext -Algorithm stopped at a point that was converged, -not to the 'desired' tolerances, but to 'acceptable' tolerances -(see Ipopt options). -$rnext -local_infeasibility $cnext -Algorithm converged to a non-feasible point -(problem may have no solution). -$rnext -user_requested_stop $cnext -This return value should not happen. -$rnext -diverging_iterates $cnext -It the iterates are diverging. -$rnext -restoration_failure $cnext -Restoration phase failed, algorithm doesn't know how to proceed. -$rnext -error_in_step_computation $cnext -An unrecoverable error occurred while Ipopt tried to -compute the search direction. -$rnext -invalid_number_detected $cnext -Algorithm received an invalid number (such as $code nan$$ or $code inf$$) -from the users function $icode%fg_info%.eval%$$ or from the CppAD evaluations -of its derivatives -(see the Ipopt option $code check_derivatives_for_naninf$$). -$rnext -internal_error $cnext -An unknown Ipopt internal error occurred. -Contact the Ipopt authors through the mailing list. -$tend - -$subhead x$$ -The $code x$$ field of $icode solution$$ has prototype -$codei% - %Vector% %solution%.x -%$$ -and its size is equal to $icode nx$$. -It is the final $latex x$$ value for the optimizer. - -$subhead zl$$ -The $code zl$$ field of $icode solution$$ has prototype -$codei% - %Vector% %solution%.zl -%$$ -and its size is equal to $icode nx$$. -It is the final Lagrange multipliers for the -lower bounds on $latex x$$. - -$subhead zu$$ -The $code zu$$ field of $icode solution$$ has prototype -$codei% - %Vector% %solution%.zu -%$$ -and its size is equal to $icode nx$$. -It is the final Lagrange multipliers for the -upper bounds on $latex x$$. - -$subhead g$$ -The $code g$$ field of $icode solution$$ has prototype -$codei% - %Vector% %solution%.g -%$$ -and its size is equal to $icode ng$$. -It is the final value for the constraint function $latex g(x)$$. - -$subhead lambda$$ -The $code lambda$$ field of $icode solution$$ has prototype -$codei% - %Vector%> %solution%.lambda -%$$ -and its size is equal to $icode ng$$. -It is the final value for the -Lagrange multipliers corresponding to the constraint function. - -$subhead obj_value$$ -The $code obj_value$$ field of $icode solution$$ has prototype -$codei% - double %solution%.obj_value -%$$ -It is the final value of the objective function $latex f(x)$$. - -$children% - example/ipopt_solve/get_started.cpp% - example/ipopt_solve/retape.cpp% - example/ipopt_solve/ode_inverse.cpp -%$$ -$head Example$$ -All the examples return true if it succeeds and false otherwise. - -$subhead get_started$$ -The file -$cref%example/ipopt_solve/get_started.cpp%ipopt_solve_get_started.cpp%$$ -is an example and test of $code ipopt::solve$$ -taken from the Ipopt manual. - -$subhead retape$$ -The file -$cref%example/ipopt_solve/retape.cpp%ipopt_solve_retape.cpp%$$ -demonstrates when it is necessary to specify -$cref/retape/ipopt_solve/options/Retape/$$ as true. - -$subhead ode_inverse$$ -The file -$cref%example/ipopt_solve/ode_inverse.cpp%ipopt_solve_ode_inverse.cpp%$$ -demonstrates using Ipopt to solve for parameters in an ODE model. - -$end -------------------------------------------------------------------------------- -*/ -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -namespace ipopt { -/*! -\file solve.hpp -\brief Implement the ipopt::solve Nonlinear Programming Solver -*/ - -/*! -Use Ipopt to Solve a Nonlinear Programming Problem - -\tparam Bvector -simple vector class with elements of type bool. - -\tparam Dvector -simple vector class with elements of type double. - -\tparam FG_eval -function object used to evaluate f(x) and g(x); see fg_eval below. -It must also support -\code - FG_eval::ADvector -\endcode -to dentify the type used for the arguments to fg_eval. - -\param options -list of options, one for each line. -Ipopt options (are optional) and have one of the following forms -\code - String name value - Numeric name value - Integer name value -\endcode -The following other possible options are listed below: -\code - Retape value -\endcode - - -\param xi -initial argument value to start optimization procedure at. - -\param xl -lower limit for argument during optimization - -\param xu -upper limit for argument during optimization - -\param gl -lower limit for g(x) during optimization. - -\param gu -upper limit for g(x) during optimization. - -\param fg_eval -function that evaluates the objective and constraints using the syntax -\code - fg_eval(fg, x) -\endcode - -\param solution -structure that holds the solution of the optimization. -*/ -template -void solve( - const std::string& options , - const Dvector& xi , - const Dvector& xl , - const Dvector& xu , - const Dvector& gl , - const Dvector& gu , - FG_eval& fg_eval , - ipopt::solve_result& solution ) -{ bool ok = true; - - typedef typename FG_eval::ADvector ADvector; - - CPPAD_ASSERT_KNOWN( - xi.size() == xl.size() && xi.size() == xu.size() , - "ipopt::solve: size of xi, xl, and xu are not all equal." - ); - CPPAD_ASSERT_KNOWN( - gl.size() == gu.size() , - "ipopt::solve: size of gl and gu are not equal." - ); - size_t nx = xi.size(); - size_t ng = gl.size(); - - // Create an IpoptApplication - using Ipopt::IpoptApplication; - Ipopt::SmartPtr app = new IpoptApplication(); - - // process the options argument - size_t begin_1, end_1, begin_2, end_2, begin_3, end_3; - begin_1 = 0; - bool retape = false; - bool sparse_forward = false; - bool sparse_reverse = false; - while( begin_1 < options.size() ) - { // split this line into tokens - while( options[begin_1] == ' ') - begin_1++; - end_1 = options.find_first_of(" \n", begin_1); - begin_2 = end_1; - while( options[begin_2] == ' ') - begin_2++; - end_2 = options.find_first_of(" \n", begin_2); - begin_3 = end_2; - while( options[begin_3] == ' ') - begin_3++; - end_3 = options.find_first_of(" \n", begin_3); - - // check for errors - CPPAD_ASSERT_KNOWN( - (end_1 != std::string::npos) & - (end_2 != std::string::npos) & - (end_3 != std::string::npos) , - "ipopt::solve: missing '\\n' at end of an option line" - ); - CPPAD_ASSERT_KNOWN( - (end_1 > begin_1) & (end_2 > begin_2) , - "ipopt::solve: an option line does not have two tokens" - ); - - // get first two tokens - std::string tok_1 = options.substr(begin_1, end_1 - begin_1); - std::string tok_2 = options.substr(begin_2, end_2 - begin_2); - - // get third token - std::string tok_3; - bool three_tok = false; - three_tok |= tok_1 == "Sparse"; - three_tok |= tok_1 == "String"; - three_tok |= tok_1 == "Numeric"; - three_tok |= tok_1 == "Integer"; - if( three_tok ) - { CPPAD_ASSERT_KNOWN( - (end_3 > begin_3) , - "ipopt::solve: a Sparse, String, Numeric, or Integer\n" - "option line does not have three tokens." - ); - tok_3 = options.substr(begin_3, end_3 - begin_3); - } - - // switch on option type - if( tok_1 == "Retape" ) - { CPPAD_ASSERT_KNOWN( - (tok_2 == "true") | (tok_2 == "false") , - "ipopt::solve: Retape value is not true or false" - ); - retape = (tok_2 == "true"); - } - else if( tok_1 == "Sparse" ) - { CPPAD_ASSERT_KNOWN( - (tok_2 == "true") | (tok_2 == "false") , - "ipopt::solve: Sparse value is not true or false" - ); - CPPAD_ASSERT_KNOWN( - (tok_3 == "forward") | (tok_3 == "reverse") , - "ipopt::solve: Sparse direction is not forward or reverse" - ); - if( tok_2 == "false" ) - { sparse_forward = false; - sparse_reverse = false; - } - else - { sparse_forward = tok_3 == "forward"; - sparse_reverse = tok_3 == "reverse"; - } - } - else if ( tok_1 == "String" ) - app->Options()->SetStringValue(tok_2.c_str(), tok_3.c_str()); - else if ( tok_1 == "Numeric" ) - { Ipopt::Number value = std::atof( tok_3.c_str() ); - app->Options()->SetNumericValue(tok_2.c_str(), value); - } - else if ( tok_1 == "Integer" ) - { Ipopt::Index value = std::atoi( tok_3.c_str() ); - app->Options()->SetIntegerValue(tok_2.c_str(), value); - } - else CPPAD_ASSERT_KNOWN( - false, - "ipopt::solve: First token is not one of\n" - "Retape, Sparse, String, Numeric, Integer" - ); - - begin_1 = end_3; - while( options[begin_1] == ' ') - begin_1++; - if( options[begin_1] != '\n' ) CPPAD_ASSERT_KNOWN( - false, - "ipopt::solve: either more than three tokens " - "or no '\\n' at end of a line" - ); - begin_1++; - } - CPPAD_ASSERT_KNOWN( - ! ( retape & (sparse_forward | sparse_reverse) ) , - "ipopt::solve: retape and sparse both true is not supported." - ); - - // Initialize the IpoptApplication and process the options - Ipopt::ApplicationReturnStatus status = app->Initialize(); - ok &= status == Ipopt::Solve_Succeeded; - if( ! ok ) - { solution.status = solve_result::unknown; - return; - } - - // Create an interface from Ipopt to this specific problem. - // Note the assumption here that ADvector is same as cppd_ipopt::ADvector - size_t nf = 1; - Ipopt::SmartPtr cppad_nlp = - new CppAD::ipopt::solve_callback( - nf, - nx, - ng, - xi, - xl, - xu, - gl, - gu, - fg_eval, - retape, - sparse_forward, - sparse_reverse, - solution - ); - - // Run the IpoptApplication - app->OptimizeTNLP(cppad_nlp); - - return; -} - -} // end ipopt namespace -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/ipopt/solve_callback.hpp b/ct_core/include/ct/external/cppad/ipopt/solve_callback.hpp deleted file mode 100644 index 10fa5960a..000000000 --- a/ct_core/include/ct/external/cppad/ipopt/solve_callback.hpp +++ /dev/null @@ -1,1192 +0,0 @@ -// $Id: solve_callback.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SOLVE_CALLBACK_HPP -# define CPPAD_SOLVE_CALLBACK_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -namespace ipopt { -/*! -\file solve_callback.hpp -\brief Class that connects ipopt::solve to Ipopt -*/ - -/*! -Class that Ipopt uses for obtaining information about this problem. - - -\section Evaluation_Methods Evaluation Methods -The set of evaluation methods for this class is -\verbatim - { eval_f, eval_grad_f, eval_g, eval_jac_g, eval_h } -\endverbatim -Note that the bool return flag for the evaluations methods -does not appear in the Ipopt documentation. -Looking at the code, it seems to be a flag telling Ipopt to abort -when the flag is false. -*/ -template -class solve_callback : public Ipopt::TNLP -{ -private: - // ------------------------------------------------------------------ - // Types used by this class - // ------------------------------------------------------------------ - /// A Scalar value used by Ipopt - typedef Ipopt::Number Number; - /// An index value used by Ipopt - typedef Ipopt::Index Index; - /// Indexing style used in Ipopt sparsity structure - typedef Ipopt::TNLP::IndexStyleEnum IndexStyleEnum; - // ------------------------------------------------------------------ - // Values directly passed in to constuctor - // ------------------------------------------------------------------ - /// dimension of the range space for f(x). - /// The objective is sum_i f_i (x). - /// Note that, at this point, there is no advantage having nf_ > 1. - const size_t nf_; - /// dimension of the domain space for f(x) and g(x) - const size_t nx_; - /// dimension of the range space for g(x) - const size_t ng_; - /// initial value for x - const Dvector& xi_; - /// lower limit for x - const Dvector& xl_; - /// upper limit for x - const Dvector& xu_; - /// lower limit for g(x) - const Dvector& gl_; - /// upper limit for g(x) - const Dvector& gu_; - /// object that evaluates f(x) and g(x) - FG_eval& fg_eval_; - /// should operation sequence be retaped for each new x. - bool retape_; - /// Should sparse methods be used to compute Jacobians and Hessians - /// with forward mode used for Jacobian. - bool sparse_forward_; - /// Should sparse methods be used to compute Jacobians and Hessians - /// with reverse mode used for Jacobian. - bool sparse_reverse_; - /// final results are returned to this structure - solve_result& solution_; - // ------------------------------------------------------------------ - // Values that are initilaized by the constructor - // ------------------------------------------------------------------ - /// AD function object that evaluates x -> [ f(x) , g(x) ] - /// If retape is false, this object is initialzed by constructor - /// otherwise it is set by cache_new_x each time it is called. - CppAD::ADFun adfun_; - /// value of x corresponding to previous new_x - Dvector x0_; - /// value of fg corresponding to previous new_x - Dvector fg0_; - // ---------------------------------------------------------------------- - // Jacobian information - // ---------------------------------------------------------------------- - /// Sparsity pattern for Jacobian of [f(x), g(x) ]. - /// If sparse is true, this pattern set by constructor and does not change. - /// Otherwise this vector has size zero. - CppAD::vectorBool pattern_jac_; - /// Row indices of [f(x), g(x)] for Jacobian of g(x) in row order. - /// (Set by constructor and not changed.) - CppAD::vector row_jac_; - /// Column indices for Jacobian of g(x), same order as row_jac_. - /// (Set by constructor and not changed.) - CppAD::vector col_jac_; - /// col_order_jac_ sorts row_jac_ and col_jac_ in column order. - /// (Set by constructor and not changed.) - CppAD::vector col_order_jac_; - /// Work vector used by SparseJacobian, stored here to avoid recalculation. - CppAD::sparse_jacobian_work work_jac_; - // ---------------------------------------------------------------------- - // Hessian information - // ---------------------------------------------------------------------- - /// Sparsity pattern for Hessian of Lagragian - /// \f[ L(x) = \sigma \sum_i f_i (x) + \sum_i \lambda_i g_i (x) \f] - /// If sparse is true, this pattern set by constructor and does not change. - /// Otherwise this vector has size zero. - CppAD::vectorBool pattern_hes_; - /// Row indices of Hessian lower left triangle in row order. - /// (Set by constructor and not changed.) - CppAD::vector row_hes_; - /// Column indices of Hessian left triangle in same order as row_hes_. - /// (Set by constructor and not changed.) - CppAD::vector col_hes_; - /// Work vector used by SparseJacobian, stored here to avoid recalculation. - CppAD::sparse_hessian_work work_hes_; - // ------------------------------------------------------------------ - // Private member functions - // ------------------------------------------------------------------ - /*! - Cache information for a new value of x. - - \param x - is the new value for x. - - \par x0_ - the elements of this vector are set to the new value for x. - - \par fg0_ - the elements of this vector are set to the new value for [f(x), g(x)] - - \par adfun_ - If retape is true, the operation sequence for this function - is changes to correspond to the argument x. - If retape is false, the operation sequence is not changed. - The zero order Taylor coefficients for this function are set - so they correspond to the argument x. - */ - void cache_new_x(const Number* x) - { size_t i; - if( retape_ ) - { // make adfun_, as well as x0_ and fg0_ correspond to this x - ADvector a_x(nx_), a_fg(nf_ + ng_); - for(i = 0; i < nx_; i++) - { x0_[i] = x[i]; - a_x[i] = x[i]; - } - CppAD::Independent(a_x); - fg_eval_(a_fg, a_x); - adfun_.Dependent(a_x, a_fg); - } - else - { // make x0_ and fg0_ correspond to this x - for(i = 0; i < nx_; i++) - x0_[i] = x[i]; - } - fg0_ = adfun_.Forward(0, x0_); - } -public: - // ---------------------------------------------------------------------- - /*! - Constructor for the interface between ipopt::solve and Ipopt - - \param nf - dimension of the range space for f(x) - - \param nx - dimension of the domain space for f(x) and g(x). - - \param ng - dimension of the range space for g(x) - - \param xi - initial value of x during the optimization procedure (size nx). - - \param xl - lower limit for x (size nx). - - \param xu - upper limit for x (size nx). - - \param gl - lower limit for g(x) (size ng). - - \param gu - upper limit for g(x) (size ng). - - \param fg_eval - function object that evaluations f(x) and g(x) using fg_eval(fg, x) - - \param retape - should the operation sequence be retaped for each argument value. - - \param sparse_forward - should sparse matrix computations be used for Jacobians and Hessians - with forward mode for Jacobian. - - \param sparse_reverse - should sparse matrix computations be used for Jacobians and Hessians - with reverse mode for Jacobian. - (sparse_forward and sparse_reverse cannot both be true). - - \param solution - object where final results are stored. - */ - solve_callback( - size_t nf , - size_t nx , - size_t ng , - const Dvector& xi , - const Dvector& xl , - const Dvector& xu , - const Dvector& gl , - const Dvector& gu , - FG_eval& fg_eval , - bool retape , - bool sparse_forward , - bool sparse_reverse , - solve_result& solution ) : - nf_ ( nf ), - nx_ ( nx ), - ng_ ( ng ), - xi_ ( xi ), - xl_ ( xl ), - xu_ ( xu ), - gl_ ( gl ), - gu_ ( gu ), - fg_eval_ ( fg_eval ), - retape_ ( retape ), - sparse_forward_ ( sparse_forward ), - sparse_reverse_ ( sparse_reverse ), - solution_ ( solution ) - { CPPAD_ASSERT_UNKNOWN( ! ( sparse_forward_ & sparse_reverse_ ) ); - - size_t i, j; - size_t nfg = nf_ + ng_; - - // initialize x0_ and fg0_ wih proper dimensions and value nan - x0_.resize(nx); - fg0_.resize(nfg); - for(i = 0; i < nx_; i++) - x0_[i] = CppAD::nan(0.0); - for(i = 0; i < nfg; i++) - fg0_[i] = CppAD::nan(0.0); - - if( ! retape_ ) - { // make adfun_ correspond to x -> [ f(x), g(x) ] - ADvector a_x(nx_), a_fg(nfg); - for(i = 0; i < nx_; i++) - a_x[i] = xi_[i]; - CppAD::Independent(a_x); - fg_eval_(a_fg, a_x); - adfun_.Dependent(a_x, a_fg); - // optimize because we will make repeated use of this tape - adfun_.optimize(); - } - if( sparse_forward_ | sparse_reverse_ ) - { CPPAD_ASSERT_UNKNOWN( ! retape ); - size_t m = nf_ + ng_; - // - // ----------------------------------------------------------- - // Jacobian - pattern_jac_.resize( m * nx_ ); - if( nx_ <= m ) - { // use forward mode to compute sparsity - - // number of bits that are packed into one unit in vectorBool - size_t n_column = vectorBool::bit_per_unit(); - - // sparsity patterns for current columns - vectorBool r(nx_ * n_column), s(m * n_column); - - // compute the sparsity pattern n_column columns at a time - size_t n_loop = (nx_ - 1) / n_column + 1; - for(size_t i_loop = 0; i_loop < n_loop; i_loop++) - { // starting column index for this iteration - size_t i_column = i_loop * n_column; - - // pattern that picks out the appropriate columns - for(i = 0; i < nx_; i++) - { for(j = 0; j < n_column; j++) - r[i * n_column + j] = (i == i_column + j); - } - s = adfun_.ForSparseJac(n_column, r); - - // fill in the corresponding columns of total_sparsity - for(i = 0; i < m; i++) - { for(j = 0; j < n_column; j++) - { if( i_column + j < nx_ ) - pattern_jac_[i * nx_ + i_column + j] = - s[i * n_column + j]; - } - } - } - } - else - { // use reverse mode to compute sparsity - - // number of bits that are packed into one unit in vectorBool - size_t n_row = vectorBool::bit_per_unit(); - - // sparsity patterns for current rows - vectorBool r(n_row * m), s(n_row * nx_); - - // compute the sparsity pattern n_row row at a time - size_t n_loop = (m - 1) / n_row + 1; - for(size_t i_loop = 0; i_loop < n_loop; i_loop++) - { // starting row index for this iteration - size_t i_row = i_loop * n_row; - - // pattern that picks out the appropriate rows - for(i = 0; i < n_row; i++) - { for(j = 0; j < m; j++) - r[i * m + j] = (i_row + i == j); - } - s = adfun_.RevSparseJac(n_row, r); - - // fill in correspoding rows of total sparsity - for(i = 0; i < n_row; i++) - { for(j = 0; j < nx_; j++) - if( i_row + i < m ) - pattern_jac_[ (i_row + i) * nx_ + j ] = - s[ i * nx_ + j]; - } - } - } - /* - { // use reverse mode to compute sparsity - CppAD::vectorBool s(m * m); - for(i = 0; i < m; i++) - { for(j = 0; j < m; j++) - s[i * m + j] = (i == j); - } - pattern_jac_ = adfun_.RevSparseJac(m, s); - } - */ - // Set row and column indices in Jacoian of [f(x), g(x)] - // for Jacobian of g(x). These indices are in row major order. - for(i = nf_; i < nfg; i++) - { for(j = 0; j < nx_; j++) - { if( pattern_jac_[ i * nx_ + j ] ) - { row_jac_.push_back(i); - col_jac_.push_back(j); - } - } - } - // Set row and column indices in Jacoian of [f(x), g(x)] - // for Jacobian of g(x). These indices are in row major order. - // ----------------------------------------------------------- - // Hessian - pattern_hes_.resize(nx_ * nx_); - - // number of bits that are packed into one unit in vectorBool - size_t n_column = vectorBool::bit_per_unit(); - - // sparsity patterns for current columns - vectorBool r(nx_ * n_column), h(nx_ * n_column); - - // sparsity pattern for range space of function - vectorBool s(m); - for(i = 0; i < m; i++) - s[i] = true; - - // compute the sparsity pattern n_column columns at a time - size_t n_loop = (nx_ - 1) / n_column + 1; - for(size_t i_loop = 0; i_loop < n_loop; i_loop++) - { // starting column index for this iteration - size_t i_column = i_loop * n_column; - - // pattern that picks out the appropriate columns - for(i = 0; i < nx_; i++) - { for(j = 0; j < n_column; j++) - r[i * n_column + j] = (i == i_column + j); - } - adfun_.ForSparseJac(n_column, r); - - // sparsity pattern corresponding to paritls w.r.t. (theta, u) - // of partial w.r.t. the selected columns - bool transpose = true; - h = adfun_.RevSparseHes(n_column, s, transpose); - - // fill in the corresponding columns of total_sparsity - for(i = 0; i < nx_; i++) - { for(j = 0; j < n_column; j++) - { if( i_column + j < nx_ ) - pattern_hes_[i * nx_ + i_column + j] = - h[i * n_column + j]; - } - } - } - // Set row and column indices for Lower triangle of Hessian - // of Lagragian. These indices are in row major order. - for(i = 0; i < nx_; i++) - { for(j = 0; j < nx_; j++) - { if( pattern_hes_[ i * nx_ + j ] ) - if( j <= i ) - { row_hes_.push_back(i); - col_hes_.push_back(j); - } - } - } - } - else - { // Set row and column indices in Jacoian of [f(x), g(x)] - // for Jacobian of g(x). These indices are in row major order. - for(i = nf_; i < nfg; i++) - { for(j = 0; j < nx_; j++) - { row_jac_.push_back(i); - col_jac_.push_back(j); - } - } - // Set row and column indices for lower triangle of Hessian. - // These indices are in row major order. - for(i = 0; i < nx_; i++) - { for(j = 0; j <= i; j++) - { row_hes_.push_back(i); - col_hes_.push_back(j); - } - } - } - - // Column order indirect sort of the Jacobian indices - col_order_jac_.resize( col_jac_.size() ); - index_sort( col_jac_, col_order_jac_ ); - } - // ----------------------------------------------------------------------- - /*! - Return dimension information about optimization problem. - - \param[out] n - is set to the value nx_. - - \param[out] m - is set to the value ng_. - - \param[out] nnz_jac_g - is set to ng_ * nx_ (sparsity not yet implemented) - - \param[out] nnz_h_lag - is set to nx_*(nx_+1)/2 (sparsity not yet implemented) - - \param[out] index_style - is set to C_STYLE; i.e., zeoro based indexing is used in the - information passed to Ipopt. - */ - virtual bool get_nlp_info( - Index& n , - Index& m , - Index& nnz_jac_g , - Index& nnz_h_lag , - IndexStyleEnum& index_style ) - { - n = static_cast(nx_); - m = static_cast(ng_); - nnz_jac_g = static_cast(row_jac_.size()); - nnz_h_lag = static_cast(row_hes_.size()); - -# ifndef NDEBUG - if( ! (sparse_forward_ | sparse_reverse_) ) - { size_t nnz = static_cast(nnz_jac_g); - CPPAD_ASSERT_UNKNOWN( nnz == ng_ * nx_); - // - nnz = static_cast(nnz_h_lag); - CPPAD_ASSERT_UNKNOWN( nnz == (nx_ * (nx_ + 1)) / 2 ); - } -# endif - - // use the fortran index style for row/col entries - index_style = C_STYLE; - - return true; - } - // ----------------------------------------------------------------------- - /*! - Return bound information about optimization problem. - - \param[in] n - is the dimension of the domain space for f(x) and g(x); i.e., - it must be equal to nx_. - - \param[out] x_l - is a vector of size nx_. - The input value of its elements does not matter. - On output, it is a copy of the lower bound for \f$ x \f$; i.e., - xl_. - - \param[out] x_u - is a vector of size nx_. - The input value of its elements does not matter. - On output, it is a copy of the upper bound for \f$ x \f$; i.e., - xu_. - - \param[in] m - is the dimension of the range space for g(x). i.e., - it must be equal to ng_. - - \param[out] g_l - is a vector of size ng_. - The input value of its elements does not matter. - On output, it is a copy of the lower bound for \f$ g(x) \f$; i.e., gl_. - - \param[out] g_u - is a vector of size ng_. - The input value of its elements does not matter. - On output, it is a copy of the upper bound for \f$ g(x) \f$; i.e, gu_. - */ - virtual bool get_bounds_info( - Index n , - Number* x_l , - Number* x_u , - Index m , - Number* g_l , - Number* g_u ) - { size_t i; - // here, the n and m we gave IPOPT in get_nlp_info are passed back - CPPAD_ASSERT_UNKNOWN(static_cast(n) == nx_); - CPPAD_ASSERT_UNKNOWN(static_cast(m) == ng_); - - // pass back bounds - for(i = 0; i < nx_; i++) - { x_l[i] = xl_[i]; - x_u[i] = xu_[i]; - } - for(i = 0; i < ng_; i++) - { g_l[i] = gl_[i]; - g_u[i] = gu_[i]; - } - - return true; - } - // ----------------------------------------------------------------------- - /*! - Return initial x value where optimiation is started. - - \param[in] n - must be equal to the domain dimension for f(x) and g(x); i.e., - it must be equal to nx_. - - \param[in] init_x - must be equal to true. - - \param[out] x - is a vector of size nx_. - The input value of its elements does not matter. - On output, it is a copy of the initial value for \f$ x \f$; i.e. xi_. - - \param[in] init_z - must be equal to false. - - \param z_L - is not used. - - \param z_U - is not used. - - \param[in] m - must be equal to the domain dimension for f(x) and g(x); i.e., - it must be equal to ng_. - - \param init_lambda - must be equal to false. - - \param lambda - is not used. - */ - virtual bool get_starting_point( - Index n , - bool init_x , - Number* x , - bool init_z , - Number* z_L , - Number* z_U , - Index m , - bool init_lambda , - Number* lambda ) - { size_t j; - - CPPAD_ASSERT_UNKNOWN(static_cast(n) == nx_ ); - CPPAD_ASSERT_UNKNOWN(static_cast(m) == ng_ ); - CPPAD_ASSERT_UNKNOWN(init_x == true); - CPPAD_ASSERT_UNKNOWN(init_z == false); - CPPAD_ASSERT_UNKNOWN(init_lambda == false); - - for(j = 0; j < nx_; j++) - x[j] = xi_[j]; - - return true; - } - // ----------------------------------------------------------------------- - /*! - Evaluate the objective fucntion f(x). - - \param[in] n - is the dimension of the argument space for f(x); i.e., must be equal nx_. - - \param[in] x - is a vector of size nx_ containing the point at which to evaluate - the function sum_i f_i (x). - - \param[in] new_x - is false if the previous call to any one of the - \ref Evaluation_Methods used the same value for x. - - \param[out] obj_value - is the value of the objective sum_i f_i (x) at this value of x. - - \return - The return value is always true; see \ref Evaluation_Methods. - */ - virtual bool eval_f( - Index n , - const Number* x , - bool new_x , - Number& obj_value ) - { size_t i; - if( new_x ) - cache_new_x(x); - // - double sum = 0.0; - for(i = 0; i < nf_; i++) - sum += fg0_[i]; - obj_value = static_cast(sum); - return true; - } - // ----------------------------------------------------------------------- - /*! - Evaluate the gradient of f(x). - - \param[in] n - is the dimension of the argument space for f(x); i.e., must be equal nx_. - - \param[in] x - has a vector of size nx_ containing the point at which to evaluate - the gradient of f(x). - - \param[in] new_x - is false if the previous call to any one of the - \ref Evaluation_Methods used the same value for x. - - \param[out] grad_f - is a vector of size nx_. - The input value of its elements does not matter. - The output value of its elements is the gradient of f(x) - at this value of. - - \return - The return value is always true; see \ref Evaluation_Methods. - */ - virtual bool eval_grad_f( - Index n , - const Number* x , - bool new_x , - Number* grad_f ) - { size_t i; - if( new_x ) - cache_new_x(x); - // - Dvector w(nf_ + ng_), dw(nx_); - for(i = 0; i < nf_; i++) - w[i] = 1.0; - for(i = 0; i < ng_; i++) - w[nf_ + i] = 0.0; - dw = adfun_.Reverse(1, w); - for(i = 0; i < nx_; i++) - grad_f[i] = dw[i]; - return true; - } - // ----------------------------------------------------------------------- - /*! - Evaluate the function g(x). - - \param[in] n - is the dimension of the argument space for g(x); i.e., must be equal nx_. - - \param[in] x - has a vector of size n containing the point at which to evaluate - the gradient of g(x). - - \param[in] new_x - is false if the previous call to any one of the - \ref Evaluation_Methods used the same value for x. - - \param[in] m - is the dimension of the range space for g(x); i.e., must be equal to ng_. - - \param[out] g - is a vector of size ng_. - The input value of its elements does not matter. - The output value of its elements is - the value of the function g(x) at this value of x. - - \return - The return value is always true; see \ref Evaluation_Methods. - */ - virtual bool eval_g( - Index n , - const Number* x , - bool new_x , - Index m , - Number* g ) - { size_t i; - if( new_x ) - cache_new_x(x); - // - for(i = 0; i < ng_; i++) - g[i] = fg0_[nf_ + i]; - return true; - } - // ----------------------------------------------------------------------- - /*! - Evaluate the Jacobian of g(x). - - \param[in] n - is the dimension of the argument space for g(x); - i.e., must be equal nx_. - - \param x - If values is not NULL, - x is a vector of size nx_ containing the point at which to evaluate - the gradient of g(x). - - \param[in] new_x - is false if the previous call to any one of the - \ref Evaluation_Methods used the same value for x. - - \param[in] m - is the dimension of the range space for g(x); - i.e., must be equal to ng_. - - \param[in] nele_jac - is the number of possibly non-zero elements in the Jacobian of g(x); - i.e., must be equal to ng_ * nx_. - - \param iRow - if values is not NULL, iRow is not defined. - if values is NULL, iRow - is a vector with size nele_jac. - The input value of its elements does not matter. - On output, - For k = 0 , ... , nele_jac-1, iRow[k] is the - base zero row index for the - k-th possibly non-zero entry in the Jacobian of g(x). - - \param jCol - if values is not NULL, jCol is not defined. - if values is NULL, jCol - is a vector with size nele_jac. - The input value of its elements does not matter. - On output, - For k = 0 , ... , nele_jac-1, jCol[k] is the - base zero column index for the - k-th possibly non-zero entry in the Jacobian of g(x). - - \param values - if \c values is not \c NULL, \c values - is a vector with size \c nele_jac. - The input value of its elements does not matter. - On output, - For k = 0 , ... , nele_jac-1, values[k] is the - value for the - k-th possibly non-zero entry in the Jacobian of g(x). - - \return - The return value is always true; see \ref Evaluation_Methods. - */ - virtual bool eval_jac_g( - Index n, - const Number* x, - bool new_x, - - Index m, - Index nele_jac, - Index* iRow, - Index *jCol, - - Number* values) - { size_t i, j, k, ell; - CPPAD_ASSERT_UNKNOWN(static_cast(m) == ng_ ); - CPPAD_ASSERT_UNKNOWN(static_cast(n) == nx_ ); - // - size_t nk = row_jac_.size(); - CPPAD_ASSERT_UNKNOWN( static_cast(nele_jac) == nk ); - // - if( new_x ) - cache_new_x(x); - - if( values == NULL ) - { for(k = 0; k < nk; k++) - { i = row_jac_[k]; - j = col_jac_[k]; - CPPAD_ASSERT_UNKNOWN( i >= nf_ ); - iRow[k] = static_cast(i - nf_); - jCol[k] = static_cast(j); - } - return true; - } - // - if( nk == 0 ) - return true; - // - if( sparse_forward_ ) - { Dvector jac(nk); - adfun_.SparseJacobianForward( - x0_ , pattern_jac_, row_jac_, col_jac_, jac, work_jac_ - ); - for(k = 0; k < nk; k++) - values[k] = jac[k]; - } - else if( sparse_reverse_ ) - { Dvector jac(nk); - adfun_.SparseJacobianReverse( - x0_ , pattern_jac_, row_jac_, col_jac_, jac, work_jac_ - ); - for(k = 0; k < nk; k++) - values[k] = jac[k]; - } - else if( nx_ < ng_ ) - { // use forward mode - Dvector x1(nx_), fg1(nf_ + ng_); - for(j = 0; j < nx_; j++) - x1[j] = 0.0; - // index in col_order_jac_ of next entry - ell = 0; - k = col_order_jac_[ell]; - for(j = 0; j < nx_; j++) - { // compute j-th column of Jacobian of g(x) - x1[j] = 1.0; - fg1 = adfun_.Forward(1, x1); - while( ell < nk && col_jac_[k] <= j ) - { CPPAD_ASSERT_UNKNOWN( col_jac_[k] == j ); - i = row_jac_[k]; - CPPAD_ASSERT_UNKNOWN( i >= nf_ ) - values[k] = fg1[i]; - ell++; - if( ell < nk ) - k = col_order_jac_[ell]; - } - x1[j] = 0.0; - } - } - else - { // user reverse mode - size_t nfg = nf_ + ng_; - // user reverse mode - Dvector w(nfg), dw(nx_); - for(i = 0; i < nfg; i++) - w[i] = 0.0; - // index in row_jac_ of next entry - k = 0; - for(i = nf_; i < nfg; i++) - { // compute i-th row of Jacobian of g(x) - w[i] = 1.0; - dw = adfun_.Reverse(1, w); - while( k < nk && row_jac_[k] <= i ) - { CPPAD_ASSERT_UNKNOWN( row_jac_[k] == i ); - j = col_jac_[k]; - values[k] = dw[j]; - k++; - } - w[i] = 0.0; - } - } - return true; - } - // ----------------------------------------------------------------------- - /*! - Evaluate the Hessian of the Lagragian - - \section The_Hessian_of_the_Lagragian The Hessian of the Lagragian - The Hessian of the Lagragian is defined as - \f[ - H(x, \sigma, \lambda ) - = - \sigma \nabla^2 f(x) + \sum_{i=0}^{m-1} \lambda_i \nabla^2 g(x)_i - \f] - - \param[in] n - is the dimension of the argument space for g(x); - i.e., must be equal nx_. - - \param x - if values is not NULL, x - is a vector of size nx_ containing the point at which to evaluate - the Hessian of the Lagragian. - - \param[in] new_x - is false if the previous call to any one of the - \ref Evaluation_Methods used the same value for x. - - \param[in] obj_factor - the value \f$ \sigma \f$ multiplying the Hessian of - f(x) in the expression for \ref The_Hessian_of_the_Lagragian. - - \param[in] m - is the dimension of the range space for g(x); - i.e., must be equal to ng_. - - \param[in] lambda - if values is not NULL, lambda - is a vector of size ng_ specifing the value of \f$ \lambda \f$ - in the expression for \ref The_Hessian_of_the_Lagragian. - - \param[in] new_lambda - is true if the previous call to eval_h had the same value for - lambda and false otherwise. - (Not currently used.) - - \param[in] nele_hess - is the number of possibly non-zero elements in the - Hessian of the Lagragian; - i.e., must be equal to nx_*(nx_+1)/2. - - \param iRow - if values is not NULL, iRow is not defined. - if values is NULL, iRow - is a vector with size nele_hess. - The input value of its elements does not matter. - On output, - For k = 0 , ... , nele_hess-1, iRow[k] is the - base zero row index for the - k-th possibly non-zero entry in the Hessian fo the Lagragian. - - \param jCol - if values is not NULL, jCol is not defined. - if values is NULL, jCol - is a vector with size nele_hess. - The input value of its elements does not matter. - On output, - For k = 0 , ... , nele_hess-1, jCol[k] is the - base zero column index for the - k-th possibly non-zero entry in the Hessian of the Lagragian. - - \param values - if values is not NULL, it - is a vector with size nele_hess. - The input value of its elements does not matter. - On output, - For k = 0 , ... , nele_hess-1, values[k] is the - value for the - k-th possibly non-zero entry in the Hessian of the Lagragian. - - \return - The return value is always true; see \ref Evaluation_Methods. - */ - virtual bool eval_h( - Index n , - const Number* x , - bool new_x , - Number obj_factor , - Index m , - const Number* lambda , - bool new_lambda , - Index nele_hess , - Index* iRow , - Index* jCol , - Number* values ) - { size_t i, j, k; - CPPAD_ASSERT_UNKNOWN(static_cast(m) == ng_ ); - CPPAD_ASSERT_UNKNOWN(static_cast(n) == nx_ ); - // - size_t nk = row_hes_.size(); - CPPAD_ASSERT_UNKNOWN( static_cast(nele_hess) == nk ); - // - if( new_x ) - cache_new_x(x); - // - if( values == NULL ) - { for(k = 0; k < nk; k++) - { i = row_hes_[k]; - j = col_hes_[k]; - iRow[k] = static_cast(i); - jCol[k] = static_cast(j); - } - return true; - } - // - if( nk == 0 ) - return true; - - // weigting vector for Lagragian - Dvector w(nf_ + ng_); - for(i = 0; i < nf_; i++) - w[i] = obj_factor; - for(i = 0; i < ng_; i++) - w[i + nf_] = lambda[i]; - // - if( sparse_forward_ | sparse_reverse_ ) - { Dvector hes(nk); - adfun_.SparseHessian( - x0_, w, pattern_hes_, row_hes_, col_hes_, hes, work_hes_ - ); - for(k = 0; k < nk; k++) - values[k] = hes[k]; - } - else - { Dvector hes(nx_ * nx_); - hes = adfun_.Hessian(x0_, w); - for(k = 0; k < nk; k++) - { i = row_hes_[k]; - j = col_hes_[k]; - values[k] = hes[i * nx_ + j]; - } - } - return true; - } - // ---------------------------------------------------------------------- - /*! - Pass solution information from Ipopt to users solution structure. - - \param[in] status - is value that the Ipopt solution status - which gets mapped to a correponding value for - \n - solution_.status - - \param[in] n - is the dimension of the domain space for f(x) and g(x); i.e., - it must be equal to nx_. - - \param[in] x - is a vector with size nx_ specifing the final solution. - This is the output value for - \n - solution_.x - - \param[in] z_L - is a vector with size nx_ specifing the Lagragian multipliers for the - constraint \f$ x^l \leq x \f$. - This is the output value for - \n - solution_.zl - - \param[in] z_U - is a vector with size nx_ specifing the Lagragian multipliers for the - constraint \f$ x \leq x^u \f$. - This is the output value for - \n - solution_.zu - - \param[in] m - is the dimension of the range space for g(x). i.e., - it must be equal to ng_. - - \param[in] g - is a vector with size ng_ containing the value of the constraint function - g(x) at the final solution x. - This is the output value for - \n - solution_.g - - \param[in] lambda - is a vector with size ng_ specifing the Lagragian multipliers for the - constraints \f$ g^l \leq g(x) \leq g^u \f$. - This is the output value for - \n - solution_.lambda - - \param[in] obj_value - is the value of the objective function f(x) at the final solution x. - This is the output value for - \n - solution_.obj_value - - \param[in] ip_data - is unspecified (by Ipopt) and hence not used. - - \param[in] ip_cq - is unspecified (by Ipopt) and hence not used. - - \par solution_[out] - this is a reference to the solution argument - in the constructor for solve_callback. - The results are stored here - (see documentation above). - */ - virtual void finalize_solution( - Ipopt::SolverReturn status , - Index n , - const Number* x , - const Number* z_L , - const Number* z_U , - Index m , - const Number* g , - const Number* lambda , - Number obj_value , - const Ipopt::IpoptData* ip_data , - Ipopt::IpoptCalculatedQuantities* ip_cq - ) - { size_t i, j; - - CPPAD_ASSERT_UNKNOWN(static_cast(n) == nx_ ); - CPPAD_ASSERT_UNKNOWN(static_cast(m) == ng_ ); - - switch(status) - { // convert status from Ipopt enum to solve_result enum - case Ipopt::SUCCESS: - solution_.status = solve_result::success; - break; - - case Ipopt::MAXITER_EXCEEDED: - solution_.status = - solve_result::maxiter_exceeded; - break; - - case Ipopt::STOP_AT_TINY_STEP: - solution_.status = - solve_result::stop_at_tiny_step; - break; - - case Ipopt::STOP_AT_ACCEPTABLE_POINT: - solution_.status = - solve_result::stop_at_acceptable_point; - break; - - case Ipopt::LOCAL_INFEASIBILITY: - solution_.status = - solve_result::local_infeasibility; - break; - - case Ipopt::USER_REQUESTED_STOP: - solution_.status = - solve_result::user_requested_stop; - break; - - case Ipopt::DIVERGING_ITERATES: - solution_.status = - solve_result::diverging_iterates; - break; - - case Ipopt::RESTORATION_FAILURE: - solution_.status = - solve_result::restoration_failure; - break; - - case Ipopt::ERROR_IN_STEP_COMPUTATION: - solution_.status = - solve_result::error_in_step_computation; - break; - - case Ipopt::INVALID_NUMBER_DETECTED: - solution_.status = - solve_result::invalid_number_detected; - break; - - case Ipopt::INTERNAL_ERROR: - solution_.status = - solve_result::internal_error; - break; - - default: - solution_.status = - solve_result::unknown; - } - - solution_.x.resize(nx_); - solution_.zl.resize(nx_); - solution_.zu.resize(nx_); - for(j = 0; j < nx_; j++) - { solution_.x[j] = x[j]; - solution_.zl[j] = z_L[j]; - solution_.zu[j] = z_U[j]; - } - solution_.g.resize(ng_); - solution_.lambda.resize(ng_); - for(i = 0; i < ng_; i++) - { solution_.g[i] = g[i]; - solution_.lambda[i] = lambda[i]; - } - solution_.obj_value = obj_value; - return; - } -}; - -} // end namespace ipopt -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/ipopt/solve_result.hpp b/ct_core/include/ct/external/cppad/ipopt/solve_result.hpp deleted file mode 100644 index 30b42778b..000000000 --- a/ct_core/include/ct/external/cppad/ipopt/solve_result.hpp +++ /dev/null @@ -1,73 +0,0 @@ -// $Id: solve_result.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SOLVE_RESULT_HPP -# define CPPAD_SOLVE_RESULT_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -namespace ipopt { -/*! -\file solve_result.hpp -Class that contains information about solve problem result -*/ - -/*! -Class that contains information about solve problem result - -\tparam Dvector -a simple vector with elements of type double -*/ -template -class solve_result -{ -public: - /// possible values for the result status - enum status_type { - not_defined, - success, - maxiter_exceeded, - stop_at_tiny_step, - stop_at_acceptable_point, - local_infeasibility, - user_requested_stop, - feasible_point_found, - diverging_iterates, - restoration_failure, - error_in_step_computation, - invalid_number_detected, - too_few_degrees_of_freedom, - internal_error, - unknown - }; - - /// possible values for solution status - status_type status; - /// the approximation solution - Dvector x; - /// Lagrange multipliers corresponding to lower bounds on x - Dvector zl; - /// Lagrange multipliers corresponding to upper bounds on x - Dvector zu; - /// value of g(x) - Dvector g; - /// Lagrange multipliers correspondiing constraints on g(x) - Dvector lambda; - /// value of f(x) - double obj_value; - /// constructor initializes solution status as not yet defined - solve_result(void) - { status = not_defined; } -}; - -} // end namespace ipopt -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/abort_recording.hpp b/ct_core/include/ct/external/cppad/local/abort_recording.hpp deleted file mode 100644 index 7d03c5329..000000000 --- a/ct_core/include/ct/external/cppad/local/abort_recording.hpp +++ /dev/null @@ -1,61 +0,0 @@ -// $Id: abort_recording.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_ABORT_RECORDING_HPP -# define CPPAD_ABORT_RECORDING_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin abort_recording$$ -$spell -$$ - -$section Abort Recording of an Operation Sequence$$ -$mindex tape$$ - - -$head Syntax$$ -$codei%AD<%Base%>::abort_recording()%$$ - -$head Purpose$$ -Sometimes it is necessary to abort the recording of an operation sequence -that started with a call of the form -$codei% - Independent(%x%) -%$$ -If such a recording is currently in progress, -$code abort_recording$$ will stop the recording and delete the -corresponding information. -Otherwise, $code abort_recording$$ has no effect. - -$children% - example/abort_recording.cpp -%$$ -$head Example$$ -The file -$cref abort_recording.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ----------------------------------------------------------------------------- -*/ - - -namespace CppAD { - template - void AD::abort_recording(void) - { ADTape* tape = AD::tape_ptr(); - if( tape != CPPAD_NULL ) - AD::tape_manage(tape_manage_delete); - } -} - -# endif diff --git a/ct_core/include/ct/external/cppad/local/abs.hpp b/ct_core/include/ct/external/cppad/local/abs.hpp deleted file mode 100644 index 21e9a4339..000000000 --- a/ct_core/include/ct/external/cppad/local/abs.hpp +++ /dev/null @@ -1,115 +0,0 @@ -// $Id: abs.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_ABS_HPP -# define CPPAD_ABS_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin abs$$ -$spell - fabs - Vec - std - faq - Taylor - Cpp - namespace - const - abs -$$ - -$section AD Absolute Value Functions: abs, fabs$$ - -$head Syntax$$ -$icode%y% = abs(%x%) -%$$ -$icode%y% = fabs(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -In the case where $icode x$$ is an AD type, -this is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Complex Types$$ -The functions $code abs$$ and $icode fabs$$ -are not defined for the base types -$code std::complex$$ or $code std::complex$$ -because the complex $code abs$$ function is not complex differentiable -(see $cref/complex types faq/Faq/Complex Types/$$). - -$head Derivative$$ -CppAD defines the derivative of the $code abs$$ function is -the $cref sign$$ function; i.e., -$latex \[ -{\rm abs}^{(1)} ( x ) = {\rm sign} (x ) = -\left\{ \begin{array}{rl} - +1 & {\rm if} \; x > 0 \\ - 0 & {\rm if} \; x = 0 \\ - -1 & {\rm if} \; x < 0 -\end{array} \right. -\] $$ -The result for $icode%x% == 0%$$ used to be a directional derivative. - -$head Example$$ -$children% - example/abs.cpp -%$$ -The file -$cref abs.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD AD::Abs (void) const -{ - AD result; - result.value_ = abs(value_); - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - if( Variable(*this) ) - { // add this operation to the tape - CPPAD_ASSERT_UNKNOWN( NumRes(AbsOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(AbsOp) == 1 ); - ADTape *tape = tape_this(); - - // corresponding operand address - tape->Rec_.PutArg(taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(AbsOp); - // make result a variable - result.tape_id_ = tape->id_; - } - return result; -} - -template -inline AD abs(const AD &x) -{ return x.Abs(); } - -template -inline AD abs(const VecAD_reference &x) -{ return abs( x.ADBase() ); } - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/abs_op.hpp b/ct_core/include/ct/external/cppad/local/abs_op.hpp deleted file mode 100644 index ec23f01ed..000000000 --- a/ct_core/include/ct/external/cppad/local/abs_op.hpp +++ /dev/null @@ -1,161 +0,0 @@ -// $Id: abs_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_ABS_OP_HPP -# define CPPAD_ABS_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file abs_op.hpp -Forward and reverse mode calculations for z = abs(x). -*/ - -/*! -Compute forward mode Taylor coefficient for result of op = AbsOp. - -The C++ source code corresponding to this operation is -\verbatim - z = abs(x) -\endverbatim - -\copydetails forward_unary1_op -*/ -template -inline void forward_abs_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AbsOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AbsOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - - for(size_t j = p; j <= q; j++) - z[j] = sign(x[0]) * x[j]; -} - -/*! -Multiple directions forward mode Taylor coefficient for op = AbsOp. - -The C++ source code corresponding to this operation is -\verbatim - z = abs(x) -\endverbatim - -\copydetails forward_unary1_op_dir -*/ -template -inline void forward_abs_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AbsOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AbsOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - z[m + ell] = sign(x[0]) * x[m + ell]; -} - -/*! -Compute zero order forward mode Taylor coefficient for result of op = AbsOp. - -The C++ source code corresponding to this operation is -\verbatim - z = abs(x) -\endverbatim - -\copydetails forward_unary1_op_0 -*/ -template -inline void forward_abs_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AbsOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AbsOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base x0 = *(taylor + i_x * cap_order); - Base* z = taylor + i_z * cap_order; - - z[0] = abs(x0); -} -/*! -Compute reverse mode partial derivatives for result of op = AbsOp. - -The C++ source code corresponding to this operation is -\verbatim - z = abs(x) -\endverbatim - -\copydetails reverse_unary1_op -*/ - -template -inline void reverse_abs_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ size_t j; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AbsOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AbsOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to result - Base* pz = partial + i_z * nc_partial; - - // do not need azmul becasue sign is either +1, -1, or zero - for(j = 0; j <= d; j++) - px[j] += sign(x[0]) * pz[j]; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/acos_op.hpp b/ct_core/include/ct/external/cppad/local/acos_op.hpp deleted file mode 100644 index 6e071625c..000000000 --- a/ct_core/include/ct/external/cppad/local/acos_op.hpp +++ /dev/null @@ -1,264 +0,0 @@ -// $Id: acos_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_ACOS_OP_HPP -# define CPPAD_ACOS_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file acos_op.hpp -Forward and reverse mode calculations for z = acos(x). -*/ - - -/*! -Compute forward mode Taylor coefficient for result of op = AcosOp. - -The C++ source code corresponding to this operation is -\verbatim - z = acos(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt(1 - x * x) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op -*/ -template -inline void forward_acos_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AcosOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AcosOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - Base* b = z - cap_order; // called y in documentation - - size_t k; - Base uj; - if( p == 0 ) - { z[0] = acos( x[0] ); - uj = Base(1) - x[0] * x[0]; - b[0] = sqrt( uj ); - p++; - } - for(size_t j = p; j <= q; j++) - { uj = Base(0); - for(k = 0; k <= j; k++) - uj -= x[k] * x[j-k]; - b[j] = Base(0); - z[j] = Base(0); - for(k = 1; k < j; k++) - { b[j] -= Base(k) * b[k] * b[j-k]; - z[j] -= Base(k) * z[k] * b[j-k]; - } - b[j] /= Base(j); - z[j] /= Base(j); - // - b[j] += uj / Base(2); - z[j] -= x[j]; - // - b[j] /= b[0]; - z[j] /= b[0]; - } -} -/*! -Multiple directions forward mode Taylor coefficient for op = AcosOp. - -The C++ source code corresponding to this operation is -\verbatim - z = acos(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt(1 - x * x) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op_dir -*/ -template -inline void forward_acos_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AcosOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AcosOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - Base* b = z - num_taylor_per_var; // called y in documentation - - size_t k, ell; - size_t m = (q-1) * r + 1; - for(ell = 0; ell < r; ell ++) - { Base uq = - 2.0 * x[m + ell] * x[0]; - for(k = 1; k < q; k++) - uq -= x[(k-1)*r+1+ell] * x[(q-k-1)*r+1+ell]; - b[m+ell] = Base(0); - z[m+ell] = Base(0); - for(k = 1; k < q; k++) - { b[m+ell] += Base(k) * b[(k-1)*r+1+ell] * b[(q-k-1)*r+1+ell]; - z[m+ell] += Base(k) * z[(k-1)*r+1+ell] * b[(q-k-1)*r+1+ell]; - } - b[m+ell] = ( uq / Base(2) - b[m+ell] / Base(q) ) / b[0]; - z[m+ell] = -( x[m+ell] + z[m+ell] / Base(q) ) / b[0]; - } -} - -/*! -Compute zero order forward mode Taylor coefficient for result of op = AcosOp. - -The C++ source code corresponding to this operation is -\verbatim - z = acos(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt( 1 - x * x ) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails forward_unary2_op_0 -*/ -template -inline void forward_acos_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AcosOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AcosOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - Base* b = z - cap_order; // called y in documentation - - z[0] = acos( x[0] ); - b[0] = sqrt( Base(1) - x[0] * x[0] ); -} -/*! -Compute reverse mode partial derivatives for result of op = AcosOp. - -The C++ source code corresponding to this operation is -\verbatim - z = acos(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt( 1 - x * x ) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails reverse_unary2_op -*/ - -template -inline void reverse_acos_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AcosOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AcosOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to first result - const Base* z = taylor + i_z * cap_order; - Base* pz = partial + i_z * nc_partial; - - // Taylor coefficients and partials corresponding to auxillary result - const Base* b = z - cap_order; // called y in documentation - Base* pb = pz - nc_partial; - - Base inv_b0 = Base(1) / b[0]; - - // number of indices to access - size_t j = d; - size_t k; - while(j) - { - // scale partials w.r.t b[j] by 1 / b[0] - pb[j] = azmul(pb[j], inv_b0); - - // scale partials w.r.t z[j] by 1 / b[0] - pz[j] = azmul(pz[j], inv_b0); - - // update partials w.r.t b^0 - pb[0] -= azmul(pz[j], z[j]) + azmul(pb[j], b[j]); - - // update partial w.r.t. x^0 - px[0] -= azmul(pb[j], x[j]); - - // update partial w.r.t. x^j - px[j] -= pz[j] + azmul(pb[j], x[0]); - - // further scale partial w.r.t. z[j] by 1 / j - pz[j] /= Base(j); - - for(k = 1; k < j; k++) - { // update partials w.r.t b^(j-k) - pb[j-k] -= Base(k) * azmul(pz[j], z[k]) + azmul(pb[j], b[k]); - - // update partials w.r.t. x^k - px[k] -= azmul(pb[j], x[j-k]); - - // update partials w.r.t. z^k - pz[k] -= Base(k) * azmul(pz[j], b[j-k]); - } - --j; - } - - // j == 0 case - px[0] -= azmul( pz[0] + azmul(pb[0], x[0]), inv_b0); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/acosh.hpp b/ct_core/include/ct/external/cppad/local/acosh.hpp deleted file mode 100644 index ab6100789..000000000 --- a/ct_core/include/ct/external/cppad/local/acosh.hpp +++ /dev/null @@ -1,96 +0,0 @@ -// $Id$ -# ifndef CPPAD_ACOSH_HPP -# define CPPAD_ACOSH_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin acosh$$ -$spell - acosh - const - Vec - std - cmath - CppAD -$$ -$section The Inverse Hyperbolic Cosine Function: acosh$$ - -$head Syntax$$ -$icode%y% = acosh(%x%)%$$ - -$head Description$$ -The inverse hyperbolic cosine function is defined by -$icode%x% == cosh(%y%)%$$. - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head CPPAD_USE_CPLUSPLUS_2011$$ - -$subhead true$$ -If this preprocessor symbol is true ($code 1$$), -and $icode x$$ is an AD type, -this is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$subhead false$$ -If this preprocessor symbol is false ($code 0$$), -CppAD uses the representation -$latex \[ -\R{acosh} (x) = \log \left( x + \sqrt{ x^2 - 1 } \right) -\] $$ -to compute this function. - -$head Example$$ -$children% - example/acosh.cpp -%$$ -The file -$cref acosh.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ -# include -# if ! CPPAD_USE_CPLUSPLUS_2011 - -// BEGIN CppAD namespace -namespace CppAD { - -template -Type acosh_template(const Type &x) -{ return CppAD::log( x + CppAD::sqrt( x * x - Type(1) ) ); -} - -inline float acosh(const float &x) -{ return acosh_template(x); } - -inline double acosh(const double &x) -{ return acosh_template(x); } - -template -inline AD acosh(const AD &x) -{ return acosh_template(x); } - -template -inline AD acosh(const VecAD_reference &x) -{ return acosh_template( x.ADBase() ); } - - -} // END CppAD namespace - -# endif // CPPAD_USE_CPLUSPLUS_2011 -# endif // CPPAD_ACOSH_INCLUDED diff --git a/ct_core/include/ct/external/cppad/local/acosh_op.hpp b/ct_core/include/ct/external/cppad/local/acosh_op.hpp deleted file mode 100644 index 351ccde81..000000000 --- a/ct_core/include/ct/external/cppad/local/acosh_op.hpp +++ /dev/null @@ -1,266 +0,0 @@ -// $Id$ -# ifndef CPPAD_ACOSH_OP_HPP -# define CPPAD_ACOSH_OP_HPP -# if CPPAD_USE_CPLUSPLUS_2011 - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file acosh_op.hpp -Forward and reverse mode calculations for z = acosh(x). -*/ - - -/*! -Compute forward mode Taylor coefficient for result of op = AcoshOp. - -The C++ source code corresponding to this operation is -\verbatim - z = acosh(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt(x * x - 1) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op -*/ -template -inline void forward_acosh_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AcoshOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AcoshOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - Base* b = z - cap_order; // called y in documentation - - size_t k; - Base uj; - if( p == 0 ) - { z[0] = acosh( x[0] ); - uj = x[0] * x[0] - Base(1); - b[0] = sqrt( uj ); - p++; - } - for(size_t j = p; j <= q; j++) - { uj = Base(0); - for(k = 0; k <= j; k++) - uj += x[k] * x[j-k]; - b[j] = Base(0); - z[j] = Base(0); - for(k = 1; k < j; k++) - { b[j] -= Base(k) * b[k] * b[j-k]; - z[j] -= Base(k) * z[k] * b[j-k]; - } - b[j] /= Base(j); - z[j] /= Base(j); - // - b[j] += uj / Base(2); - z[j] += x[j]; - // - b[j] /= b[0]; - z[j] /= b[0]; - } -} -/*! -Multiple directions forward mode Taylor coefficient for op = AcoshOp. - -The C++ source code corresponding to this operation is -\verbatim - z = acosh(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt(x * x - 1) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op_dir -*/ -template -inline void forward_acosh_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AcoshOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AcoshOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - Base* b = z - num_taylor_per_var; // called y in documentation - - size_t k, ell; - size_t m = (q-1) * r + 1; - for(ell = 0; ell < r; ell ++) - { Base uq = 2.0 * x[m + ell] * x[0]; - for(k = 1; k < q; k++) - uq += x[(k-1)*r+1+ell] * x[(q-k-1)*r+1+ell]; - b[m+ell] = Base(0); - z[m+ell] = Base(0); - for(k = 1; k < q; k++) - { b[m+ell] += Base(k) * b[(k-1)*r+1+ell] * b[(q-k-1)*r+1+ell]; - z[m+ell] += Base(k) * z[(k-1)*r+1+ell] * b[(q-k-1)*r+1+ell]; - } - b[m+ell] = ( uq / Base(2) - b[m+ell] / Base(q) ) / b[0]; - z[m+ell] = ( x[m+ell] - z[m+ell] / Base(q) ) / b[0]; - } -} - -/*! -Compute zero order forward mode Taylor coefficient for result of op = AcoshOp. - -The C++ source code corresponding to this operation is -\verbatim - z = acosh(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt( x * x - 1 ) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails forward_unary2_op_0 -*/ -template -inline void forward_acosh_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AcoshOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AcoshOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - Base* b = z - cap_order; // called y in documentation - - z[0] = acosh( x[0] ); - b[0] = sqrt( x[0] * x[0] - Base(1) ); -} -/*! -Compute reverse mode partial derivatives for result of op = AcoshOp. - -The C++ source code corresponding to this operation is -\verbatim - z = acosh(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt( x * x - 1 ) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails reverse_unary2_op -*/ - -template -inline void reverse_acosh_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AcoshOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AcoshOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to first result - const Base* z = taylor + i_z * cap_order; - Base* pz = partial + i_z * nc_partial; - - // Taylor coefficients and partials corresponding to auxillary result - const Base* b = z - cap_order; // called y in documentation - Base* pb = pz - nc_partial; - - Base inv_b0 = Base(1) / b[0]; - - // number of indices to access - size_t j = d; - size_t k; - while(j) - { - // scale partials w.r.t b[j] by 1 / b[0] - pb[j] = azmul(pb[j], inv_b0); - - // scale partials w.r.t z[j] by 1 / b[0] - pz[j] = azmul(pz[j], inv_b0); - - // update partials w.r.t b^0 - pb[0] -= azmul(pz[j], z[j]) + azmul(pb[j], b[j]); - - // update partial w.r.t. x^0 - px[0] += azmul(pb[j], x[j]); - - // update partial w.r.t. x^j - px[j] += pz[j] + azmul(pb[j], x[0]); - - // further scale partial w.r.t. z[j] by 1 / j - pz[j] /= Base(j); - - for(k = 1; k < j; k++) - { // update partials w.r.t b^(j-k) - pb[j-k] -= Base(k) * azmul(pz[j], z[k]) + azmul(pb[j], b[k]); - - // update partials w.r.t. x^k - px[k] += azmul(pb[j], x[j-k]); - - // update partials w.r.t. z^k - pz[k] -= Base(k) * azmul(pz[j], b[j-k]); - } - --j; - } - - // j == 0 case - px[0] += azmul(pz[0] + azmul(pb[0], x[0]), inv_b0); -} - -} // END_CPPAD_NAMESPACE -# endif -# endif diff --git a/ct_core/include/ct/external/cppad/local/ad.hpp b/ct_core/include/ct/external/cppad/local/ad.hpp deleted file mode 100644 index 883d7e740..000000000 --- a/ct_core/include/ct/external/cppad/local/ad.hpp +++ /dev/null @@ -1,293 +0,0 @@ -// $Id: ad.hpp 3760 2015-12-01 04:12:28Z bradbell $ -# ifndef CPPAD_AD_HPP -# define CPPAD_AD_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// simple AD operations that must be defined for AD as well as base class -# include -# include - -// define the template classes that are used by the AD template class -# include -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -typedef enum { - tape_manage_new, - tape_manage_delete, - tape_manage_clear -} tape_manage_job; - -template -class AD { - // enable use of AD in parallel mode - template - friend void parallel_ad(void); - - // template friend functions where template parameter is not bound - template - friend void Independent(VectorAD &x, size_t abort_op_index); - - // one argument functions - friend bool Parameter - (const AD &u); - friend bool Parameter - (const VecAD &u); - friend bool Variable - (const AD &u); - friend bool Variable - (const VecAD &u); - friend int Integer - (const AD &u); - friend AD Var2Par - (const AD &u); - - // power function - friend AD pow - (const AD &x, const AD &y); - - // azmul function - friend AD azmul - (const AD &x, const AD &y); - - // order determining functions, see ordered.hpp - friend bool GreaterThanZero (const AD &x); - friend bool GreaterThanOrZero (const AD &x); - friend bool LessThanZero (const AD &x); - friend bool LessThanOrZero (const AD &x); - friend bool abs_geq - (const AD& x, const AD& y); - - // The identical property functions, see identical.hpp - friend bool IdenticalPar (const AD &x); - friend bool IdenticalZero (const AD &x); - friend bool IdenticalOne (const AD &x); - friend bool IdenticalEqualPar - (const AD &x, const AD &y); - - // EqualOpSeq function - friend bool EqualOpSeq - (const AD &u, const AD &v); - - // NearEqual function - friend bool NearEqual ( - const AD &x, const AD &y, const Base &r, const Base &a); - - friend bool NearEqual ( - const Base &x, const AD &y, const Base &r, const Base &a); - - friend bool NearEqual ( - const AD &x, const Base &y, const Base &r, const Base &a); - - // CondExp function - friend AD CondExpOp ( - enum CompareOp cop , - const AD &left , - const AD &right , - const AD &trueCase , - const AD &falseCase - ); - - // classes - friend class ADTape; - friend class ADFun; - friend class atomic_base; - friend class discrete; - friend class VecAD; - friend class VecAD_reference; - - // arithematic binary operators - friend AD operator + - (const AD &left, const AD &right); - friend AD operator - - (const AD &left, const AD &right); - friend AD operator * - (const AD &left, const AD &right); - friend AD operator / - (const AD &left, const AD &right); - - // comparison operators - friend bool operator < - (const AD &left, const AD &right); - friend bool operator <= - (const AD &left, const AD &right); - friend bool operator > - (const AD &left, const AD &right); - friend bool operator >= - (const AD &left, const AD &right); - friend bool operator == - (const AD &left, const AD &right); - friend bool operator != - (const AD &left, const AD &right); - - // input operator - friend std::istream& operator >> - (std::istream &is, AD &x); - - // output operations - friend std::ostream& operator << - (std::ostream &os, const AD &x); - friend void PrintFor ( - const AD& flag , - const char* before , - const AD& var , - const char* after - ); -public: - // type of value - typedef Base value_type; - - // implicit default constructor - inline AD(void); - - // use default implicit copy constructor and assignment operator - // inline AD(const AD &x); - // inline AD& operator=(const AD &x); - - // implicit construction and assingment from base type - inline AD(const Base &b); - inline AD& operator=(const Base &b); - - // implicit contructor and assignment from VecAD::reference - inline AD(const VecAD_reference &x); - inline AD& operator=(const VecAD_reference &x); - -# if CPPAD_DEPRECATED - // implicit construction from some other type (depricated) - template inline AD(const T &t); -# else - // explicit construction from some other type (depricated) - template inline explicit AD(const T &t); -# endif - - // assignment from some other type - template inline AD& operator=(const T &right); - - // base type corresponding to an AD object - friend Base Value (const AD &x); - - // computed assignment operators - inline AD& operator += (const AD &right); - inline AD& operator -= (const AD &right); - inline AD& operator *= (const AD &right); - inline AD& operator /= (const AD &right); - - // unary operators - inline AD operator +(void) const; - inline AD operator -(void) const; - - // destructor - ~AD(void) - { } - - // interface so these functions need not be friends - inline AD Abs(void) const; - inline AD acos(void) const; - inline AD asin(void) const; - inline AD atan(void) const; - inline AD cos(void) const; - inline AD cosh(void) const; - inline AD exp(void) const; - inline AD fabs(void) const; - inline AD log(void) const; - inline AD sin(void) const; - inline AD Sign(void) const; - inline AD sinh(void) const; - inline AD sqrt(void) const; - inline AD tan(void) const; - inline AD tanh(void) const; -# if CPPAD_USE_CPLUSPLUS_2011 - inline AD erf(void) const; - inline AD asinh(void) const; - inline AD acosh(void) const; - inline AD atanh(void) const; - inline AD expm1(void) const; - inline AD log1p(void) const; -# endif - - // ---------------------------------------------------------- - // static public member functions - - // abort current AD recording - static void abort_recording(void); - - // set the maximum number of OpenMP threads (deprecated) - static void omp_max_thread(size_t number); - - // These functions declared public so can be accessed by user through - // a macro interface and are not intended for direct use. - // The macro interface is documented in bool_fun.hpp. - // Developer documentation for these fucntions is in bool_fun.hpp - static inline bool UnaryBool( - bool FunName(const Base &x), - const AD &x - ); - static inline bool BinaryBool( - bool FunName(const Base &x, const Base &y), - const AD &x , const AD &y - ); - -private: - // value_ corresponding to this object - Base value_; - - // Tape identifier corresponding to taddr - tape_id_t tape_id_; - - // taddr_ in tape for this variable - addr_t taddr_; - // - // Make this variable a parameter - // - void make_parameter(void) - { CPPAD_ASSERT_UNKNOWN( Variable(*this) ); // currently a var - tape_id_ = 0; - } - // - // Make this parameter a new variable - // - void make_variable(size_t id, size_t taddr) - { CPPAD_ASSERT_UNKNOWN( Parameter(*this) ); // currently a par - CPPAD_ASSERT_UNKNOWN( taddr > 0 ); // sure valid taddr - - taddr_ = taddr; - tape_id_ = id; - } - // --------------------------------------------------------------- - // tape linking functions - // - // not static - inline ADTape* tape_this(void) const; - // - // static - inline static tape_id_t** tape_id_handle(size_t thread); - inline static tape_id_t* tape_id_ptr(size_t thread); - inline static ADTape** tape_handle(size_t thread); - static ADTape* tape_manage(tape_manage_job job); - inline static ADTape* tape_ptr(void); - inline static ADTape* tape_ptr(tape_id_t tape_id); -}; -// --------------------------------------------------------------------------- - -} // END_CPPAD_NAMESPACE - -// tape linking private functions -# include - -// operations that expect the AD template class to be defined - - -# endif diff --git a/ct_core/include/ct/external/cppad/local/ad_assign.hpp b/ct_core/include/ct/external/cppad/local/ad_assign.hpp deleted file mode 100644 index 9dbd88e0e..000000000 --- a/ct_core/include/ct/external/cppad/local/ad_assign.hpp +++ /dev/null @@ -1,141 +0,0 @@ -// $Id: ad_assign.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_AD_ASSIGN_HPP -# define CPPAD_AD_ASSIGN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ------------------------------------------------------------------------------- - -$begin ad_assign$$ -$spell - Vec - const -$$ - - -$section AD Assignment Operator$$ -$mindex assign Base VecAD$$ - -$head Syntax$$ -$icode%y% = %x%$$ - -$head Purpose$$ -Assigns the value in $icode x$$ to the object $icode y$$. -In either case, - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Type% &%x% -%$$ -where $icode Type$$ is -$codei%VecAD<%Base%>::reference%$$, -$codei%AD<%Base%>%$$, -$icode Base$$, -or any type that has an implicit constructor of the form -$icode%Base%(%x%)%$$. - -$head y$$ -The target $icode y$$ has prototype -$codei% - AD<%Base%> %y% -%$$ - -$head Example$$ -$children% - example/ad_assign.cpp -%$$ -The file $cref ad_assign.cpp$$ contain examples and tests of these operations. -It test returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------- -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -/*! -\file ad_assign.hpp -AD constructors and and copy operations. -*/ - -/*! -\page AD_default_assign -Use default assignment operator -because they may be optimized better than the code below: -\code -template -inline AD& AD::operator=(const AD &right) -{ value_ = right.value_; - tape_id_ = right.tape_id_; - taddr_ = right.taddr_; - - return *this; -} -\endcode -*/ - -/*! -Assignment to Base type value. - -\tparam Base -Base type for this AD object. - -\param b -is the Base type value being assignment to this AD object. -The tape identifier will be an invalid tape identifier, -so this object is initially a parameter. -*/ -template -inline AD& AD::operator=(const Base &b) -{ value_ = b; - tape_id_ = 0; - - // check that this is a parameter - CPPAD_ASSERT_UNKNOWN( Parameter(*this) ); - - return *this; -} - -/*! -Assignment to an ADVec element drops the vector information. - -\tparam Base -Base type for this AD object. -*/ -template -inline AD& AD::operator=(const VecAD_reference &x) -{ return *this = x.ADBase(); } - -/*! -Assignment from any other type, converts to Base type, and then uses assignment -from Base type. - -\tparam Base -Base type for this AD object. - -\tparam T -is the the type that is being assigned to AD. -There must be an assignment for Base from Type. - -\param t -is the object that is being assigned to an AD object. -*/ -template -template -inline AD& AD::operator=(const T &t) -{ return *this = Base(t); } - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/ad_binary.hpp b/ct_core/include/ct/external/cppad/local/ad_binary.hpp deleted file mode 100644 index 8d353cdd2..000000000 --- a/ct_core/include/ct/external/cppad/local/ad_binary.hpp +++ /dev/null @@ -1,145 +0,0 @@ -// $Id: ad_binary.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_AD_BINARY_HPP -# define CPPAD_AD_BINARY_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin ad_binary$$ -$spell - Op - VecAD - const -$$ - -$section AD Binary Arithmetic Operators$$ -$mindex + add plus - subtract minus * multiply times / divide$$ - - - - - - - -$head Syntax$$ -$icode%z% = %x% %Op% %y%$$ - -$head Purpose$$ -Performs arithmetic operations where either $icode x$$ or $icode y$$ -has type -$codei%AD<%Base%>%$$ or -$cref%VecAD::reference%VecAD%VecAD::reference%$$. - -$head Op$$ -The operator $icode Op$$ is one of the following -$table -$bold Op$$ $cnext $bold Meaning$$ $rnext -$code +$$ $cnext $icode z$$ is $icode x$$ plus $icode y$$ $rnext -$code -$$ $cnext $icode z$$ is $icode x$$ minus $icode y$$ $rnext -$code *$$ $cnext $icode z$$ is $icode x$$ times $icode y$$ $rnext -$code /$$ $cnext $icode z$$ is $icode x$$ divided by $icode y$$ -$tend - -$head Base$$ -The type $icode Base$$ is determined by the operand that -has type $codei%AD<%Base%>%$$ or $codei%VecAD<%Base%>::reference%$$. - -$head x$$ -The operand $icode x$$ has the following prototype -$codei% - const %Type% &%x% -%$$ -where $icode Type$$ is -$codei%VecAD<%Base%>::reference%$$, -$codei%AD<%Base%>%$$, -$icode Base$$, or -$code double$$. - -$head y$$ -The operand $icode y$$ has the following prototype -$codei% - const %Type% &%y% -%$$ -where $icode Type$$ is -$codei%VecAD<%Base%>::reference%$$, -$codei%AD<%Base%>%$$, -$icode Base$$, or -$code double$$. - - -$head z$$ -The result $icode z$$ has the following prototype -$codei% - %Type% %z% -%$$ -where $icode Type$$ is -$codei%AD<%Base%>%$$. - -$head Operation Sequence$$ -This is an $cref/atomic/glossary/Operation/Atomic/$$ -$cref/AD of Base/glossary/AD of Base/$$ operation -and hence it is part of the current -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$children% - example/add.cpp% - example/sub.cpp% - example/mul.cpp% - example/div.cpp -%$$ - -$head Example$$ -The following files contain examples and tests of these functions. -Each test returns true if it succeeds and false otherwise. -$table -$rref add.cpp$$ -$rref sub.cpp$$ -$rref mul.cpp$$ -$rref div.cpp$$ -$tend - -$head Derivative$$ -If $latex f$$ and $latex g$$ are -$cref/Base functions/glossary/Base Function/$$ - -$subhead Addition$$ -$latex \[ - \D{[ f(x) + g(x) ]}{x} = \D{f(x)}{x} + \D{g(x)}{x} -\] $$ - -$subhead Subtraction$$ -$latex \[ - \D{[ f(x) - g(x) ]}{x} = \D{f(x)}{x} - \D{g(x)}{x} -\] $$ - -$subhead Multiplication$$ -$latex \[ - \D{[ f(x) * g(x) ]}{x} = g(x) * \D{f(x)}{x} + f(x) * \D{g(x)}{x} -\] $$ - -$subhead Division$$ -$latex \[ - \D{[ f(x) / g(x) ]}{x} = - [1/g(x)] * \D{f(x)}{x} - [f(x)/g(x)^2] * \D{g(x)}{x} -\] $$ - -$end ------------------------------------------------------------------------------ -*/ -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/local/ad_ctor.hpp b/ct_core/include/ct/external/cppad/local/ad_ctor.hpp deleted file mode 100644 index 13f4223d7..000000000 --- a/ct_core/include/ct/external/cppad/local/ad_ctor.hpp +++ /dev/null @@ -1,178 +0,0 @@ -// $Id: ad_ctor.hpp 3760 2015-12-01 04:12:28Z bradbell $ -# ifndef CPPAD_AD_CTOR_HPP -# define CPPAD_AD_CTOR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ------------------------------------------------------------------------------- - -$begin ad_ctor$$ -$spell - cppad - ctor - initializes - Vec - const -$$ - - -$section AD Constructors $$ -$mindex convert Base VecAD$$ - -$head Syntax$$ -$codei%AD<%Base%> %y%() -%$$ -$codei%AD<%Base%> %y%(%x%) -%$$ - -$head Purpose$$ -creates a new $codei%AD<%Base%>%$$ object $icode y$$ -and initializes its value as equal to $icode x$$. - -$head x$$ - -$subhead implicit$$ -There is an implicit constructor where $icode x$$ has one of the following -prototypes: -$codei% - const %Base%& %x% - const VecAD<%Base%>& %x% -%$$ - -$subhead explicit$$ -There is an explicit constructor where $icode x$$ has prototype -$codei% - const %Type%& %x% -%$$ -for any type that has an explicit constructor of the form -$icode%Base%(%x%)%$$. - -$subhead Deprecated 2013-12-31$$ -If you set $cref/cppad_deprecated/cmake/cppad_deprecated/$$ -to be $code YES$$ during the install procedure, -you will get an implicit constructor with prototype -$codei% - const %Type%& %x% -%$$ -for any type that has an explicit constructor of the form -$icode%Base%(%x%)%$$. - -$head y$$ -The target $icode y$$ has prototype -$codei% - AD<%Base%> %y% -%$$ - -$head Example$$ -$children% - example/ad_ctor.cpp -%$$ -The files $cref ad_ctor.cpp$$ contain examples and tests of these operations. -It test returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------- -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -/*! -\file ad_ctor.hpp -AD constructors and and copy operations. -*/ - -/*! -\page AD_default_ctor -Use default copy constructor -because they may be optimized better than the code below: -\code -template -inline AD::AD(const AD &x) -{ - value_ = x.value_; - tape_id_ = x.tape_id_; - taddr_ = x.taddr_; - - return; -} -\endcode -*/ - -/*! -Default Constructor. - -\tparam Base -Base type for this AD object. -*/ -template -inline AD::AD(void) -: value_() -, tape_id_(0) -, taddr_(0) -{ } - - -/*! -Constructor from Base type. - -\tparam Base -Base type for this AD object. - -\param b -is the Base type value corresponding to this AD object. -The tape identifier will be an invalid tape identifier, -so this object is initially a parameter. -*/ -template -inline AD::AD(const Base &b) -: value_(b) -, tape_id_(0) -, taddr_(0) -{ // check that this is a parameter - CPPAD_ASSERT_UNKNOWN( Parameter(*this) ); -} - -/*! -Constructor from an ADVec element drops the vector information. - -\tparam Base -Base type for this AD object. -*/ -template -inline AD::AD(const VecAD_reference &x) -{ *this = x.ADBase(); } - -/*! -Constructor from any other type, converts to Base type, and uses constructor -from Base type. - -\tparam Base -Base type for this AD object. - -\tparam T -is the the type that is being converted to AD. -There must be a constructor for Base from Type. - -\param t -is the object that is being converted from T to AD. -*/ -template -template -inline AD::AD(const T &t) -: value_(Base(t)) -, tape_id_(0) -, taddr_(0) -{ } - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/ad_fun.hpp b/ct_core/include/ct/external/cppad/local/ad_fun.hpp deleted file mode 100644 index d82a13e91..000000000 --- a/ct_core/include/ct/external/cppad/local/ad_fun.hpp +++ /dev/null @@ -1,624 +0,0 @@ -// $Id: ad_fun.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_AD_FUN_HPP -# define CPPAD_AD_FUN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin ADFun$$ -$spell - xk - Ind - bool - taylor_ - sizeof - const - std - ind_taddr_ - dep_taddr_ -$$ - -$spell -$$ - -$section ADFun Objects$$ - - -$head Purpose$$ -An AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$ -is stored in an $code ADFun$$ object by its $cref FunConstruct$$. -The $code ADFun$$ object can then be used to calculate function values, -derivative values, and other values related to the corresponding function. - -$childtable% - cppad/local/independent.hpp% - cppad/local/fun_construct.hpp% - cppad/local/dependent.hpp% - cppad/local/abort_recording.hpp% - omh/seq_property.omh% - cppad/local/fun_eval.hpp% - cppad/local/drivers.hpp% - cppad/local/fun_check.hpp% - cppad/local/optimize.hpp% - cppad/local/check_for_nan.hpp -%$$ - -$end -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file ad_fun.hpp -File used to define the ADFun class. -*/ - -/*! -Class used to hold function objects - -\tparam Base -A function object has a recording of AD operations. -It does it calculations using \c Base operations. -*/ - -template -class ADFun { -// ------------------------------------------------------------ -// Private member variables -private: - /// Has this ADFun object been optmized - bool has_been_optimized_; - - /// Check for nan's and report message to user (default value is true). - bool check_for_nan_; - - /// If zero, ignoring comparison operators. Otherwise is the - /// compare change count at which to store the operator index. - size_t compare_change_count_; - - /// If compare_change_count_ is zero, compare_change_number_ is also zero. - /// Otherwise, it is set to the number of comparison operations that had a - /// different result during the subsequent zero order forward. - size_t compare_change_number_; - - /// If compare_change_count is zero, compare_change_op_index_ is also - /// zero. Otherwise it is the operator index for the comparison operator - //// that corresponded to the number changing from count-1 to count. - size_t compare_change_op_index_; - - /// number of orders stored in taylor_ - size_t num_order_taylor_; - - /// maximum number of orders that will fit in taylor_ - size_t cap_order_taylor_; - - /// number of directions stored in taylor_ - size_t num_direction_taylor_; - - /// number of variables in the recording (play_) - size_t num_var_tape_; - - /// tape address for the independent variables - CppAD::vector ind_taddr_; - - /// tape address and parameter flag for the dependent variables - CppAD::vector dep_taddr_; - - /// which dependent variables are actually parameters - CppAD::vector dep_parameter_; - - /// results of the forward mode calculations - pod_vector taylor_; - - /// which operations can be conditionally skipped - /// Set during forward pass of order zero - pod_vector cskip_op_; - - /// Variable on the tape corresponding to each vecad load operation - /// (if zero, the operation corresponds to a parameter). - pod_vector load_op_; - - /// the operation sequence corresponding to this object - player play_; - - /// Packed results of the forward mode Jacobian sparsity calculations. - /// for_jac_sparse_pack_.n_set() != 0 implies other sparsity results - /// are empty - sparse_pack for_jac_sparse_pack_; - - /// Set results of the forward mode Jacobian sparsity calculations - /// for_jac_sparse_set_.n_set() != 0 implies for_sparse_pack_ is empty. - CPPAD_INTERNAL_SPARSE_SET for_jac_sparse_set_; - -// ------------------------------------------------------------ -// Private member functions - - /// change the operation sequence corresponding to this object - template - void Dependent(ADTape *tape, const ADvector &y); - - // ------------------------------------------------------------ - // vector of bool version of ForSparseJac - // (see doxygen in for_sparse_jac.hpp) - template - void ForSparseJacCase( - bool set_type , - bool transpose , - bool dependency, - size_t q , - const VectorSet& r , - VectorSet& s - ); - // vector of std::set version of ForSparseJac - // (see doxygen in for_sparse_jac.hpp) - template - void ForSparseJacCase( - const std::set& set_type , - bool transpose , - bool dependency, - size_t q , - const VectorSet& r , - VectorSet& s - ); - // ------------------------------------------------------------ - // vector of bool version of RevSparseJac - // (see doxygen in rev_sparse_jac.hpp) - template - void RevSparseJacCase( - bool set_type , - bool transpose , - bool dependency, - size_t p , - const VectorSet& s , - VectorSet& r - ); - // vector of std::set version of RevSparseJac - // (see doxygen in rev_sparse_jac.hpp) - template - void RevSparseJacCase( - const std::set& set_type , - bool transpose , - bool dependency, - size_t p , - const VectorSet& s , - VectorSet& r - ); - // ------------------------------------------------------------ - // vector of bool version of RevSparseHes - // (see doxygen in rev_sparse_hes.hpp) - template - void RevSparseHesCase( - bool set_type , - bool transpose , - size_t q , - const VectorSet& s , - VectorSet& h - ); - // vector of std::set version of RevSparseHes - // (see doxygen in rev_sparse_hes.hpp) - template - void RevSparseHesCase( - const std::set& set_type , - bool transpose , - size_t q , - const VectorSet& s , - VectorSet& h - ); - // ------------------------------------------------------------ - // Forward mode version of SparseJacobian - // (see doxygen in sparse_jacobian.hpp) - template - size_t SparseJacobianFor( - const VectorBase& x , - VectorSet& p_transpose , - const VectorSize& row , - const VectorSize& col , - VectorBase& jac , - sparse_jacobian_work& work - ); - // Reverse mode version of SparseJacobian - // (see doxygen in sparse_jacobian.hpp) - template - size_t SparseJacobianRev( - const VectorBase& x , - VectorSet& p , - const VectorSize& row , - const VectorSize& col , - VectorBase& jac , - sparse_jacobian_work& work - ); - // ------------------------------------------------------------ - // combined sparse_set, sparse_list and sparse_pack version of - // SparseHessian (see doxygen in sparse_hessian.hpp) - template - size_t SparseHessianCompute( - const VectorBase& x , - const VectorBase& w , - VectorSet& sparsity , - const VectorSize& row , - const VectorSize& col , - VectorBase& hes , - sparse_hessian_work& work - ); -// ------------------------------------------------------------ -public: - /// copy constructor - ADFun(const ADFun& g) - : num_var_tape_(0) - { CppAD::ErrorHandler::Call( - true, - __LINE__, - __FILE__, - "ADFun(const ADFun& g)", - "Attempting to use the ADFun copy constructor.\n" - "Perhaps you are passing an ADFun object " - "by value instead of by reference." - ); - } - - /// default constructor - ADFun(void); - - // assignment operator - // (see doxygen in fun_construct.hpp) - void operator=(const ADFun& f); - - /// sequence constructor - template - ADFun(const ADvector &x, const ADvector &y); - - /// destructor - ~ADFun(void) - { } - - /// set value of check_for_nan_ - void check_for_nan(bool value) - { check_for_nan_ = value; } - bool check_for_nan(void) const - { return check_for_nan_; } - - /// assign a new operation sequence - template - void Dependent(const ADvector &x, const ADvector &y); - - /// forward mode user API, one order multiple directions. - template - VectorBase Forward(size_t q, size_t r, const VectorBase& x); - - /// forward mode user API, multiple directions one order. - template - VectorBase Forward(size_t q, - const VectorBase& x, std::ostream& s = std::cout - ); - - /// reverse mode sweep - template - VectorBase Reverse(size_t p, const VectorBase &v); - - // forward mode Jacobian sparsity - // (see doxygen documentation in for_sparse_jac.hpp) - template - VectorSet ForSparseJac( - size_t q, const VectorSet &r, bool transpose = false, - bool dependency = false - ); - // reverse mode Jacobian sparsity - // (see doxygen documentation in rev_sparse_jac.hpp) - template - VectorSet RevSparseJac( - size_t q, const VectorSet &s, bool transpose = false, - bool dependency = false - ); - // reverse mode Hessian sparsity - // (see doxygen documentation in rev_sparse_hes.hpp) - template - VectorSet RevSparseHes( - size_t q, const VectorSet &s, bool transpose = false - ); - // internal set sparsity version of RevSparseHes - // (used by checkpoint functions only) - void RevSparseHesCheckpoint( - size_t q , - vector& s , - bool transpose , - CPPAD_INTERNAL_SPARSE_SET& h - ); - // internal set sparsity version of RevSparseJac - // (used by checkpoint functions only) - void RevSparseJacCheckpoint( - size_t q , - CPPAD_INTERNAL_SPARSE_SET& r , - bool transpose , - bool dependency , - CPPAD_INTERNAL_SPARSE_SET& s - ); - // internal set sparsity version of RevSparseJac - // (used by checkpoint functions only) - void ForSparseJacCheckpoint( - size_t q , - CPPAD_INTERNAL_SPARSE_SET& r , - bool transpose , - bool dependency , - CPPAD_INTERNAL_SPARSE_SET& s - ); - - /// amount of memory used for Jacobain sparsity pattern - size_t size_forward_bool(void) const - { return for_jac_sparse_pack_.memory(); } - - /// free memory used for Jacobain sparsity pattern - void size_forward_bool(size_t zero) - { CPPAD_ASSERT_KNOWN( - zero == 0, - "size_forward_bool: argument not equal to zero" - ); - for_jac_sparse_pack_.resize(0, 0); - } - - /// total number of elements used for Jacobian sparsity pattern - size_t size_forward_set(void) const - { return for_jac_sparse_set_.number_elements(); } - - /// free memory used for Jacobain sparsity pattern - void size_forward_set(size_t zero) - { CPPAD_ASSERT_KNOWN( - zero == 0, - "size_forward_bool: argument not equal to zero" - ); - for_jac_sparse_set_.resize(0, 0); - } - - /// number of operators in the operation sequence - size_t size_op(void) const - { return play_.num_op_rec(); } - - /// number of operator arguments in the operation sequence - size_t size_op_arg(void) const - { return play_.num_op_arg_rec(); } - - /// amount of memory required for the operation sequence - size_t size_op_seq(void) const - { return play_.Memory(); } - - /// number of parameters in the operation sequence - size_t size_par(void) const - { return play_.num_par_rec(); } - - /// number taylor coefficient orders calculated - size_t size_order(void) const - { return num_order_taylor_; } - - /// number taylor coefficient directions calculated - size_t size_direction(void) const - { return num_direction_taylor_; } - - /// number of characters in the operation sequence - size_t size_text(void) const - { return play_.num_text_rec(); } - - /// number of variables in opertion sequence - size_t size_var(void) const - { return num_var_tape_; } - - /// number of VecAD indices in the operation sequence - size_t size_VecAD(void) const - { return play_.num_vec_ind_rec(); } - - /// set number of orders currently allocated (user API) - void capacity_order(size_t c); - - /// set number of orders and directions currently allocated - void capacity_order(size_t c, size_t r); - - /// number of variables in conditional expressions that can be skipped - size_t number_skip(void); - - /// number of independent variables - size_t Domain(void) const - { return ind_taddr_.size(); } - - /// number of dependent variables - size_t Range(void) const - { return dep_taddr_.size(); } - - /// is variable a parameter - bool Parameter(size_t i) - { CPPAD_ASSERT_KNOWN( - i < dep_taddr_.size(), - "Argument to Parameter is >= dimension of range space" - ); - return dep_parameter_[i]; - } - - /// Deprecated: number of comparison operations that changed - /// for the previous zero order forward (than when function was recorded) - size_t CompareChange(void) const - { return compare_change_number_; } - - /// count as which to store operator index - void compare_change_count(size_t count) - { compare_change_count_ = count; - compare_change_number_ = 0; - compare_change_op_index_ = 0; - } - - /// number of comparison operations that changed - size_t compare_change_number(void) const - { return compare_change_number_; } - - /// operator index for the count-th comparison change - size_t compare_change_op_index(void) const - { if( has_been_optimized_ ) - return 0; - return compare_change_op_index_; - } - - /// calculate entire Jacobian - template - VectorBase Jacobian(const VectorBase &x); - - /// calculate Hessian for one component of f - template - VectorBase Hessian(const VectorBase &x, const VectorBase &w); - template - VectorBase Hessian(const VectorBase &x, size_t i); - - /// forward mode calculation of partial w.r.t one domain component - template - VectorBase ForOne( - const VectorBase &x , - size_t j ); - - /// reverse mode calculation of derivative of one range component - template - VectorBase RevOne( - const VectorBase &x , - size_t i ); - - /// forward mode calculation of a subset of second order partials - template - VectorBase ForTwo( - const VectorBase &x , - const VectorSize_t &J , - const VectorSize_t &K ); - - /// reverse mode calculation of a subset of second order partials - template - VectorBase RevTwo( - const VectorBase &x , - const VectorSize_t &I , - const VectorSize_t &J ); - - /// calculate sparse Jacobians - template - VectorBase SparseJacobian( - const VectorBase &x - ); - template - VectorBase SparseJacobian( - const VectorBase &x , - const VectorSet &p - ); - template - size_t SparseJacobianForward( - const VectorBase& x , - const VectorSet& p , - const VectorSize& r , - const VectorSize& c , - VectorBase& jac , - sparse_jacobian_work& work - ); - template - size_t SparseJacobianReverse( - const VectorBase& x , - const VectorSet& p , - const VectorSize& r , - const VectorSize& c , - VectorBase& jac , - sparse_jacobian_work& work - ); - - /// calculate sparse Hessians - template - VectorBase SparseHessian( - const VectorBase& x , - const VectorBase& w - ); - template - VectorBase SparseHessian( - const VectorBase& x , - const VectorBase& w , - const VectorBool& p - ); - template - size_t SparseHessian( - const VectorBase& x , - const VectorBase& w , - const VectorSet& p , - const VectorSize& r , - const VectorSize& c , - VectorBase& hes , - sparse_hessian_work& work - ); - - // Optimize the tape - // (see doxygen documentation in optimize.hpp) - void optimize(const std::string& options = ""); - // ------------------- Deprecated ----------------------------- - - /// deprecated: assign a new operation sequence - template - void Dependent(const ADvector &y); - - /// Deprecated: number of variables in opertion sequence - size_t Size(void) const - { return num_var_tape_; } - - /// Deprecated: # taylor_ coefficients currently stored - /// (per variable,direction) - size_t Order(void) const - { return num_order_taylor_ - 1; } - - /// Deprecated: amount of memory for this object - /// Note that an approximation is used for the std::set memory - size_t Memory(void) const - { size_t pervar = cap_order_taylor_ * sizeof(Base) - + for_jac_sparse_pack_.memory() - + 3 * sizeof(size_t) * for_jac_sparse_set_.number_elements(); - size_t total = num_var_tape_ * pervar + play_.Memory(); - return total; - } - - /// Deprecated: # taylor_ coefficient orderss stored - /// (per variable,direction) - size_t taylor_size(void) const - { return num_order_taylor_; } - - /// Deprecated: Does this AD operation sequence use - /// VecAD::reference operands - bool use_VecAD(void) const - { return play_.num_vec_ind_rec() > 0; } - - /// Deprecated: # taylor_ coefficient orders calculated - /// (per variable,direction) - size_t size_taylor(void) const - { return num_order_taylor_; } - - /// Deprecated: set number of orders currently allocated - /// (per variable,direction) - void capacity_taylor(size_t per_var); -}; -// --------------------------------------------------------------------------- - -} // END_CPPAD_NAMESPACE - -// non-user interfaces -# include -# include -# include -# include -# include -# include -# include - -// user interfaces -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/local/ad_io.hpp b/ct_core/include/ct/external/cppad/local/ad_io.hpp deleted file mode 100644 index ef9b6279c..000000000 --- a/ct_core/include/ct/external/cppad/local/ad_io.hpp +++ /dev/null @@ -1,224 +0,0 @@ -// $Id: ad_io.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_AD_IO_HPP -# define CPPAD_AD_IO_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin ad_input$$ -$spell - VecAD - std - istream - const -$$ - - -$section AD Output Stream Operator$$ -$mindex >> input write$$ - -$head Syntax$$ -$icode%is% >> %x%$$ - - -$head Purpose$$ -Sets $icode x$$ to a $cref/parameter/glossary/Parameter/$$ -with value $icode b$$ corresponding to -$codei% - %is% >> %b% -%$$ -where $icode b$$ is a $icode Base$$ object. -It is assumed that this $icode Base$$ input operation returns -a reference to $icode is$$. - -$head is$$ -The operand $icode is$$ has prototype -$codei% - std::istream& %is% -%$$ - -$head x$$ -The operand $icode x$$ has one of the following prototypes -$codei% - AD<%Base%>& %x% -%$$ - -$head Result$$ -The result of this operation can be used as a reference to $icode is$$. -For example, if the operand $icode y$$ has prototype -$codei% - AD<%Base%> %y% -%$$ -then the syntax -$codei% - %is% >> %x% >> %y% -%$$ -will first read the $icode Base$$ value of $icode x$$ from $icode is$$, -and then read the $icode Base$$ value to $icode y$$. - -$head Operation Sequence$$ -The result of this operation is not an -$cref/AD of Base/glossary/AD of Base/$$ object. -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Example$$ -$children% - example/ad_input.cpp -%$$ -The file -$cref ad_input.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------- -$begin ad_output$$ -$spell - VecAD - std - ostream - const -$$ - - -$section AD Output Stream Operator$$ -$mindex <<$$ - -$head Syntax$$ -$icode%os% << %x%$$ - - -$head Purpose$$ -Writes the $icode Base$$ value, corresponding to $icode x$$, -to the output stream $icode os$$. - -$head Assumption$$ -If $icode b$$ is a $icode Base$$ object, -$codei% - %os% << %b% -%$$ -returns a reference to $icode os$$. - -$head os$$ -The operand $icode os$$ has prototype -$codei% - std::ostream& %os% -%$$ - -$head x$$ -The operand $icode x$$ has one of the following prototypes -$codei% - const AD<%Base%>& %x% - const VecAD<%Base%>::reference& %x% -%$$ - -$head Result$$ -The result of this operation can be used as a reference to $icode os$$. -For example, if the operand $icode y$$ has prototype -$codei% - AD<%Base%> %y% -%$$ -then the syntax -$codei% - %os% << %x% << %y% -%$$ -will output the value corresponding to $icode x$$ -followed by the value corresponding to $icode y$$. - -$head Operation Sequence$$ -The result of this operation is not an -$cref/AD of Base/glossary/AD of Base/$$ object. -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Example$$ -$children% - example/ad_output.cpp -%$$ -The file -$cref ad_output.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------- -*/ -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file ad_io.hpp -AD input and ouput stream operators. -*/ -// --------------------------------------------------------------------------- -/*! -Read an AD object from an input stream. - -\tparam Base -Base type for the AD object. - -\param is [in,out] -Is the input stream from which that value is read. - -\param x [out] -is the object that is being set to a value. -Upone return, x.value_ is read from the input stream -and x.tape_is_ is zero; i.e., x is a parameter. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -std::istream& operator >> (std::istream& is, AD& x) -{ // like assignment to a base type value - x.tape_id_ = 0; - CPPAD_ASSERT_UNKNOWN( Parameter(x) ); - return (is >> x.value_); -} -// --------------------------------------------------------------------------- -/*! -Write an AD object to an output stream. - -\tparam Base -Base type for the AD object. - -\param os [in,out] -Is the output stream to which that value is written. - -\param x -is the object that is being written to the output stream. -This is equivalent to writing x.value_ to the output stream. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -std::ostream& operator << (std::ostream &os, const AD &x) -{ return (os << x.value_); } -// --------------------------------------------------------------------------- -/*! -Write a VecAD_reference object to an output stream. - -\tparam Base -Base type for the VecAD_reference object. - -\param os [in,out] -Is the output stream to which that value is written. - -\param x -is the element of the VecAD object that is being written to the output stream. -This is equivalent to writing the corresponing Base value to the stream. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -std::ostream& operator << (std::ostream &os, const VecAD_reference &x) -{ return (os << x.ADBase()); } - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/ad_tape.hpp b/ct_core/include/ct/external/cppad/local/ad_tape.hpp deleted file mode 100644 index a306c21b9..000000000 --- a/ct_core/include/ct/external/cppad/local/ad_tape.hpp +++ /dev/null @@ -1,220 +0,0 @@ -// $Id: ad_tape.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_AD_TAPE_HPP -# define CPPAD_AD_TAPE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -/*! -Class used to hold tape that records AD operations. - -\tparam Base -An AD object is used to recording AD operations. -*/ - -template -class ADTape { - // Friends ============================================================= - - // classes ------------------------------------------------------------- - friend class AD; - friend class ADFun; - friend class atomic_base; - friend class discrete; - friend class VecAD; - friend class VecAD_reference; - - // functions ----------------------------------------------------------- - // PrintFor - friend void PrintFor ( - const AD& flag , - const char* before , - const AD& var , - const char* after - ); - // CondExpOp - friend AD CondExpOp ( - enum CompareOp cop , - const AD &left , - const AD &right , - const AD &trueCase , - const AD &falseCase - ); - // pow - friend AD pow - (const AD &x, const AD &y); - // azmul - friend AD azmul - (const AD &x, const AD &y); - // Parameter - friend bool Parameter - (const AD &u); - // Variable - friend bool Variable - (const AD &u); - // operators ----------------------------------------------------------- - // arithematic binary operators - friend AD operator + - (const AD &left, const AD &right); - friend AD operator - - (const AD &left, const AD &right); - friend AD operator * - (const AD &left, const AD &right); - friend AD operator / - (const AD &left, const AD &right); - - // comparison operators - friend bool operator < - (const AD &left, const AD &right); - friend bool operator <= - (const AD &left, const AD &right); - friend bool operator > - (const AD &left, const AD &right); - friend bool operator >= - (const AD &left, const AD &right); - friend bool operator == - (const AD &left, const AD &right); - friend bool operator != - (const AD &left, const AD &right); - // ====================================================================== - -// -------------------------------------------------------------------------- -private: - // ---------------------------------------------------------------------- - // private data - /*! - Unique identifier for this tape. It is always greater than - CPPAD_MAX_NUM_THREADS, and different for every tape (even ones that have - been deleted). In addition, id_ % CPPAD_MAX_NUM_THREADS is the thread - number for this tape. Set by Independent and effectively const - */ - tape_id_t id_; - /// Number of independent variables in this tapes reconding. - /// Set by Independent and effectively const - size_t size_independent_; - /// This is where the information is recorded. - recorder Rec_; - // ---------------------------------------------------------------------- - // private functions - // - // add a parameter to the tape - size_t RecordParOp(const Base &x); - - // see CondExp.h - void RecordCondExp( - enum CompareOp cop , - AD &returnValue , - const AD &left , - const AD &right , - const AD &trueCase , - const AD &falseCase - ); - - // place a VecAD object in the tape - size_t AddVec( - size_t length, - const pod_vector& data - ); - -public: - // default constructor and destructor - - // public function only used by CppAD::Independent - template - void Independent(VectorADBase &u); - template - void Independent(VectorADBase &u, size_t abort_op_index); - -}; -// --------------------------------------------------------------------------- -// Private functions -// - -/*! -Place a parameter in the tape. - -On rare occations it is necessary to place a parameter in the tape; e.g., -when it is one of the dependent variabes. - -\param z -value of the parameter that we are placing in the tape. - -\return -variable index (for this recording) correpsonding to the parameter. - -\par 2DO -All these operates are preformed in \c Rec_, so we should -move this routine from ADTape to recorder. -*/ -template -size_t ADTape::RecordParOp(const Base &z) -{ size_t z_taddr; - size_t ind; - CPPAD_ASSERT_UNKNOWN( NumRes(ParOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(ParOp) == 1 ); - z_taddr = Rec_.PutOp(ParOp); - ind = Rec_.PutPar(z); - Rec_.PutArg(ind); - - return z_taddr; -} - -/*! -Put initialization for a VecAD object in the tape. - -This routine should be called once for each VecAD object when just -before it changes from a parameter to a variable. - -\param length -size of the VecAD object. - -\param data -initial values for the VecAD object -(values before it becomes a variable). - -\return -index of the start of this vector in the list of vector indices. -The value for this vector index is the length of the vector. -There are \c length indices following for this vector. -The values for these vector indices are the corresponding -parameter indices in the tape for the initial value of the corresponding -vec_ad element. - -\par 2DO -All these operates are preformed in \c Rec_, so we should -move this routine from ADTape to recorder. -*/ -template -size_t ADTape::AddVec(size_t length, const pod_vector& data) -{ CPPAD_ASSERT_UNKNOWN( length > 0 ); - size_t i; - size_t value_index; - - // store the length in VecInd - size_t start = Rec_.PutVecInd(length); - - // store indices of the values in VecInd - for(i = 0; i < length; i++) - { - value_index = Rec_.PutPar( data[i] ); - Rec_.PutVecInd( value_index ); - } - - // return the taddr of the length (where the vector starts) - return start; -} - -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/ad_to_string.hpp b/ct_core/include/ct/external/cppad/local/ad_to_string.hpp deleted file mode 100644 index c0c60cb72..000000000 --- a/ct_core/include/ct/external/cppad/local/ad_to_string.hpp +++ /dev/null @@ -1,71 +0,0 @@ -// $Id$ -# ifndef CPPAD_AD_TO_STRING_HPP -# define CPPAD_AD_TO_STRING_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin ad_to_string$$ -$spell - const - std -$$ - -$section Convert An AD or Base Type to String$$ - -$head Syntax$$ -$icode%s% = to_string(%value%)%$$. - -$head See Also$$ -$cref to_string$$, $cref base_to_string$$ - -$head value$$ -The argument $icode value$$ has prototype -$codei% - const AD<%Base%>& %value% - const %Base%& %value% -%$$ -where $icode Base$$ is a type that supports the -$cref base_to_string$$ type requirement. - -$head s$$ -The return value has prototype -$codei% - std::string %s% -%$$ -and contains a representation of the specified $icode value$$. -If $icode value$$ is an AD type, -the result has the same precision as for the $icode Base$$ type. - -$head Example$$ -The file $cref to_string.cpp$$ -includes an example and test of $code to_string$$ with AD types. -It returns true if it succeeds and false otherwise. - -$end -*/ -# include -# include - -namespace CppAD { - - // Template definition is in cppad/utility/to_string.hpp. - // Partial specialzation for AD types - template - struct to_string_struct< CppAD::AD > - { std::string operator()(const CppAD::AD& value) - { to_string_struct ts; - return ts( Value( Var2Par( value ) ) ); } - }; - -} - -# endif diff --git a/ct_core/include/ct/external/cppad/local/ad_valued.hpp b/ct_core/include/ct/external/cppad/local/ad_valued.hpp deleted file mode 100644 index 1f21b1fb1..000000000 --- a/ct_core/include/ct/external/cppad/local/ad_valued.hpp +++ /dev/null @@ -1,49 +0,0 @@ -// $Id: ad_valued.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_AD_VALUED_HPP -# define CPPAD_AD_VALUED_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin ADValued$$ -$spell -$$ - - -$section AD Valued Operations and Functions$$ - -$comment atomic.omh includes atomic_base.omh which atomic_base.hpp$$ -$childtable% - cppad/local/arithmetic.hpp% - cppad/local/standard_math.hpp% - cppad/local/cond_exp.hpp% - cppad/local/discrete.hpp% - cppad/local/numeric_limits.hpp% - omh/atomic.omh -%$$ - -$end -*/ - -// include MathOther.h after CondExp.h because some MathOther.h routines use -// CondExp.h and CondExp.h is not sufficently declared in Declare.h - -# include -# include -# include -# include -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/local/add.hpp b/ct_core/include/ct/external/cppad/local/add.hpp deleted file mode 100644 index 07a2530b7..000000000 --- a/ct_core/include/ct/external/cppad/local/add.hpp +++ /dev/null @@ -1,97 +0,0 @@ -// $Id: add.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_ADD_HPP -# define CPPAD_ADD_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD operator + (const AD &left , const AD &right) -{ - // compute the Base part of this AD object - AD result; - result.value_ = left.value_ + right.value_; - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - // check if there is a recording in progress - ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return result; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = left.tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // result = variable + variable - CPPAD_ASSERT_UNKNOWN( NumRes(AddvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(AddvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(left.taddr_, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(AddvvOp); - // make result a variable - result.tape_id_ = tape_id; - } - else if( IdenticalZero(right.value_) ) - { // result = variable + 0 - result.make_variable(left.tape_id_, left.taddr_); - } - else - { // result = variable + parameter - // = parameter + variable - CPPAD_ASSERT_UNKNOWN( NumRes(AddpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(AddpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(p, left.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(AddpvOp); - // make result a variable - result.tape_id_ = tape_id; - } - } - else if( var_right ) - { if( IdenticalZero(left.value_) ) - { // result = 0 + variable - result.make_variable(right.tape_id_, right.taddr_); - } - else - { // result = parameter + variable - CPPAD_ASSERT_UNKNOWN( NumRes(AddpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(AddpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left.value_); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(AddpvOp); - // make result a variable - result.tape_id_ = tape_id; - } - } - return result; -} - -// convert other cases into the case above -CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR(+) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/add_eq.hpp b/ct_core/include/ct/external/cppad/local/add_eq.hpp deleted file mode 100644 index 94e5cd3aa..000000000 --- a/ct_core/include/ct/external/cppad/local/add_eq.hpp +++ /dev/null @@ -1,92 +0,0 @@ -// $Id: add_eq.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_ADD_EQ_HPP -# define CPPAD_ADD_EQ_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD& AD::operator += (const AD &right) -{ - // compute the Base part - Base left; - left = value_; - value_ += right.value_; - - // check if there is a recording in progress - ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return *this; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // this = variable + variable - CPPAD_ASSERT_UNKNOWN( NumRes(AddvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(AddvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(taddr_, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(AddvvOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - else if( ! IdenticalZero( right.value_ ) ) - { // this = variable + parameter - // = parameter + variable - CPPAD_ASSERT_UNKNOWN( NumRes(AddpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(AddpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(p, taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(AddpvOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - } - else if( var_right ) - { if( IdenticalZero(left) ) - { // this = 0 + right - make_variable(right.tape_id_, right.taddr_); - } - else - { // this = parameter + variable - CPPAD_ASSERT_UNKNOWN( NumRes(AddpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(AddpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(AddpvOp); - // make this a variable - tape_id_ = tape_id; - } - } - return *this; -} - -CPPAD_FOLD_ASSIGNMENT_OPERATOR(+=) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/add_op.hpp b/ct_core/include/ct/external/cppad/local/add_op.hpp deleted file mode 100644 index 9ff521ebb..000000000 --- a/ct_core/include/ct/external/cppad/local/add_op.hpp +++ /dev/null @@ -1,339 +0,0 @@ -// $Id: add_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_ADD_OP_HPP -# define CPPAD_ADD_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file add_op.hpp -Forward and reverse mode calculations for z = x + y. -*/ - -// --------------------------- Addvv ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = AddvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x + y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_binary_op -*/ - -template -inline void forward_addvv_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AddvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AddvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - for(size_t j = p; j <= q; j++) - z[j] = x[j] + y[j]; -} -/*! -Multiple directions forward mode Taylor coefficients for op = AddvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x + y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_binary_op_dir -*/ - -template -inline void forward_addvv_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AddvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AddvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - - // Taylor coefficients corresponding to arguments and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + arg[0] * num_taylor_per_var; - Base* y = taylor + arg[1] * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - - size_t m = (q-1)*r + 1 ; - for(size_t ell = 0; ell < r; ell++) - z[m+ell] = x[m+ell] + y[m+ell]; -} - -/*! -Compute zero order forward mode Taylor coefficients for result of op = AddvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x + y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_binary_op_0 -*/ - -template -inline void forward_addvv_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AddvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AddvvOp) == 1 ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = x[0] + y[0]; -} - -/*! -Compute reverse mode partial derivatives for result of op = AddvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x + y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails reverse_binary_op -*/ - -template -inline void reverse_addvv_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AddvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AddvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Partial derivatives corresponding to arguments and result - Base* px = partial + arg[0] * nc_partial; - Base* py = partial + arg[1] * nc_partial; - Base* pz = partial + i_z * nc_partial; - - // number of indices to access - size_t i = d + 1; - while(i) - { --i; - px[i] += pz[i]; - py[i] += pz[i]; - } -} - -// --------------------------- Addpv ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = AddpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x + y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op -*/ -template -inline void forward_addpv_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AddpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AddpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to arguments and result - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - if( p == 0 ) - { // Paraemter value - Base x = parameter[ arg[0] ]; - z[0] = x + y[0]; - p++; - } - for(size_t j = p; j <= q; j++) - z[j] = y[j]; -} -/*! -Multiple directions forward mode Taylor coefficients for op = AddpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x + y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op_dir -*/ -template -inline void forward_addpv_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AddpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AddpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to arguments and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - size_t m = (q-1) * r + 1; - Base* y = taylor + arg[1] * num_taylor_per_var + m; - Base* z = taylor + i_z * num_taylor_per_var + m; - - for(size_t ell = 0; ell < r; ell++) - z[ell] = y[ell]; -} -/*! -Compute zero order forward mode Taylor coefficient for result of op = AddpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x + y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op_0 -*/ - -template -inline void forward_addpv_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AddpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AddpvOp) == 1 ); - - // Paraemter value - Base x = parameter[ arg[0] ]; - - // Taylor coefficients corresponding to arguments and result - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = x + y[0]; -} - -/*! -Compute reverse mode partial derivative for result of op = AddpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x + y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails reverse_binary_op -*/ - -template -inline void reverse_addpv_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AddvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AddvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Partial derivatives corresponding to arguments and result - Base* py = partial + arg[1] * nc_partial; - Base* pz = partial + i_z * nc_partial; - - // number of indices to access - size_t i = d + 1; - while(i) - { --i; - py[i] += pz[i]; - } -} - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/arithmetic.hpp b/ct_core/include/ct/external/cppad/local/arithmetic.hpp deleted file mode 100644 index 292282a94..000000000 --- a/ct_core/include/ct/external/cppad/local/arithmetic.hpp +++ /dev/null @@ -1,43 +0,0 @@ -// $Id: arithmetic.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_ARITHMETIC_HPP -# define CPPAD_ARITHMETIC_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin Arithmetic$$ -$spell - Op - const -$$ - - - -$section AD Arithmetic Operators and Computed Assignments$$ - -$childtable% - cppad/local/unary_plus.hpp% - cppad/local/unary_minus.hpp% - cppad/local/ad_binary.hpp% - cppad/local/compute_assign.hpp -%$$ - -$end -------------------------------------------------------------------------------- -*/ -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/local/asin_op.hpp b/ct_core/include/ct/external/cppad/local/asin_op.hpp deleted file mode 100644 index d9d8fea73..000000000 --- a/ct_core/include/ct/external/cppad/local/asin_op.hpp +++ /dev/null @@ -1,264 +0,0 @@ -// $Id: asin_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_ASIN_OP_HPP -# define CPPAD_ASIN_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file asin_op.hpp -Forward and reverse mode calculations for z = asin(x). -*/ - - -/*! -Compute forward mode Taylor coefficient for result of op = AsinOp. - -The C++ source code corresponding to this operation is -\verbatim - z = asin(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt(1 - x * x) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op -*/ -template -inline void forward_asin_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AsinOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AsinOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - Base* b = z - cap_order; // called y in documentation - - size_t k; - Base uj; - if( p == 0 ) - { z[0] = asin( x[0] ); - uj = Base(1) - x[0] * x[0]; - b[0] = sqrt( uj ); - p++; - } - for(size_t j = p; j <= q; j++) - { uj = Base(0); - for(k = 0; k <= j; k++) - uj -= x[k] * x[j-k]; - b[j] = Base(0); - z[j] = Base(0); - for(k = 1; k < j; k++) - { b[j] -= Base(k) * b[k] * b[j-k]; - z[j] -= Base(k) * z[k] * b[j-k]; - } - b[j] /= Base(j); - z[j] /= Base(j); - // - b[j] += uj / Base(2); - z[j] += x[j]; - // - b[j] /= b[0]; - z[j] /= b[0]; - } -} -/*! -Multiple directions forward mode Taylor coefficient for op = AsinOp. - -The C++ source code corresponding to this operation is -\verbatim - z = asin(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt(1 - x * x) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op_dir -*/ -template -inline void forward_asin_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AcosOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AcosOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - Base* b = z - num_taylor_per_var; // called y in documentation - - size_t k, ell; - size_t m = (q-1) * r + 1; - for(ell = 0; ell < r; ell ++) - { Base uq = - 2.0 * x[m + ell] * x[0]; - for(k = 1; k < q; k++) - uq -= x[(k-1)*r+1+ell] * x[(q-k-1)*r+1+ell]; - b[m+ell] = Base(0); - z[m+ell] = Base(0); - for(k = 1; k < q; k++) - { b[m+ell] += Base(k) * b[(k-1)*r+1+ell] * b[(q-k-1)*r+1+ell]; - z[m+ell] += Base(k) * z[(k-1)*r+1+ell] * b[(q-k-1)*r+1+ell]; - } - b[m+ell] = ( uq / Base(2) - b[m+ell] / Base(q) ) / b[0]; - z[m+ell] = ( x[m+ell] - z[m+ell] / Base(q) ) / b[0]; - } -} - -/*! -Compute zero order forward mode Taylor coefficient for result of op = AsinOp. - -The C++ source code corresponding to this operation is -\verbatim - z = asin(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt( 1 - x * x ) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails forward_unary2_op_0 -*/ -template -inline void forward_asin_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AsinOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AsinOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - Base* b = z - cap_order; // called y in documentation - - z[0] = asin( x[0] ); - b[0] = sqrt( Base(1) - x[0] * x[0] ); -} -/*! -Compute reverse mode partial derivatives for result of op = AsinOp. - -The C++ source code corresponding to this operation is -\verbatim - z = asin(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt( 1 - x * x ) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails reverse_unary2_op -*/ - -template -inline void reverse_asin_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AsinOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AsinOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to first result - const Base* z = taylor + i_z * cap_order; - Base* pz = partial + i_z * nc_partial; - - // Taylor coefficients and partials corresponding to auxillary result - const Base* b = z - cap_order; // called y in documentation - Base* pb = pz - nc_partial; - - Base inv_b0 = Base(1) / b[0]; - - // number of indices to access - size_t j = d; - size_t k; - while(j) - { - // scale partials w.r.t b[j] by 1 / b[0] - pb[j] = azmul(pb[j], inv_b0); - - // scale partials w.r.t z[j] by 1 / b[0] - pz[j] = azmul(pz[j], inv_b0); - - // update partials w.r.t b^0 - pb[0] -= azmul(pz[j], z[j]) + azmul(pb[j], b[j]); - - // update partial w.r.t. x^0 - px[0] -= azmul(pb[j], x[j]); - - // update partial w.r.t. x^j - px[j] += pz[j] - azmul(pb[j], x[0]); - - // further scale partial w.r.t. z[j] by 1 / j - pz[j] /= Base(j); - - for(k = 1; k < j; k++) - { // update partials w.r.t b^(j-k) - pb[j-k] -= Base(k) * azmul(pz[j], z[k]) + azmul(pb[j], b[k]); - - // update partials w.r.t. x^k - px[k] -= azmul(pb[j], x[j-k]); - - // update partials w.r.t. z^k - pz[k] -= Base(k) * azmul(pz[j], b[j-k]); - } - --j; - } - - // j == 0 case - px[0] += azmul(pz[0] - azmul(pb[0], x[0]), inv_b0); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/asinh.hpp b/ct_core/include/ct/external/cppad/local/asinh.hpp deleted file mode 100644 index de1f0cfb7..000000000 --- a/ct_core/include/ct/external/cppad/local/asinh.hpp +++ /dev/null @@ -1,97 +0,0 @@ -// $Id$ -# ifndef CPPAD_ASINH_HPP -# define CPPAD_ASINH_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- - -$begin asinh$$ -$spell - asinh - const - Vec - std - cmath - CppAD -$$ -$section The Inverse Hyperbolic Sine Function: asinh$$ - -$head Syntax$$ -$icode%y% = asinh(%x%)%$$ - -$head Description$$ -The inverse hyperbolic sine function is defined by -$icode%x% == sinh(%y%)%$$. - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head CPPAD_USE_CPLUSPLUS_2011$$ - -$subhead true$$ -If this preprocessor symbol is true ($code 1$$), -and $icode x$$ is an AD type, -this is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$subhead false$$ -If this preprocessor symbol is false ($code 0$$), -CppAD uses the representation -$latex \[ -\R{asinh} (x) = \log \left( x + \sqrt{ 1 + x^2 } \right) -\] $$ -to compute this function. - -$head Example$$ -$children% - example/asinh.cpp -%$$ -The file -$cref asinh.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ -# include -# if ! CPPAD_USE_CPLUSPLUS_2011 - -// BEGIN CppAD namespace -namespace CppAD { - -template -Type asinh_template(const Type &x) -{ return CppAD::log( x + CppAD::sqrt( Type(1) + x * x ) ); -} - -inline float asinh(const float &x) -{ return asinh_template(x); } - -inline double asinh(const double &x) -{ return asinh_template(x); } - -template -inline AD asinh(const AD &x) -{ return asinh_template(x); } - -template -inline AD asinh(const VecAD_reference &x) -{ return asinh_template( x.ADBase() ); } - - -} // END CppAD namespace - -# endif // CPPAD_USE_CPLUSPLUS_2011 -# endif // CPPAD_ASINH_INCLUDED diff --git a/ct_core/include/ct/external/cppad/local/asinh_op.hpp b/ct_core/include/ct/external/cppad/local/asinh_op.hpp deleted file mode 100644 index efb1c400c..000000000 --- a/ct_core/include/ct/external/cppad/local/asinh_op.hpp +++ /dev/null @@ -1,266 +0,0 @@ -// $Id$ -# ifndef CPPAD_ASINH_OP_HPP -# define CPPAD_ASINH_OP_HPP -# if CPPAD_USE_CPLUSPLUS_2011 - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file asinh_op.hpp -Forward and reverse mode calculations for z = asinh(x). -*/ - - -/*! -Compute forward mode Taylor coefficient for result of op = AsinhOp. - -The C++ source code corresponding to this operation is -\verbatim - z = asinh(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt(1 + x * x) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op -*/ -template -inline void forward_asinh_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AsinhOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AsinhOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - Base* b = z - cap_order; // called y in documentation - - size_t k; - Base uj; - if( p == 0 ) - { z[0] = asinh( x[0] ); - uj = Base(1) + x[0] * x[0]; - b[0] = sqrt( uj ); - p++; - } - for(size_t j = p; j <= q; j++) - { uj = Base(0); - for(k = 0; k <= j; k++) - uj += x[k] * x[j-k]; - b[j] = Base(0); - z[j] = Base(0); - for(k = 1; k < j; k++) - { b[j] -= Base(k) * b[k] * b[j-k]; - z[j] -= Base(k) * z[k] * b[j-k]; - } - b[j] /= Base(j); - z[j] /= Base(j); - // - b[j] += uj / Base(2); - z[j] += x[j]; - // - b[j] /= b[0]; - z[j] /= b[0]; - } -} -/*! -Multiple directions forward mode Taylor coefficient for op = AsinhOp. - -The C++ source code corresponding to this operation is -\verbatim - z = asinh(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt(1 + x * x) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op_dir -*/ -template -inline void forward_asinh_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AcosOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AcosOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - Base* b = z - num_taylor_per_var; // called y in documentation - - size_t k, ell; - size_t m = (q-1) * r + 1; - for(ell = 0; ell < r; ell ++) - { Base uq = 2.0 * x[m + ell] * x[0]; - for(k = 1; k < q; k++) - uq += x[(k-1)*r+1+ell] * x[(q-k-1)*r+1+ell]; - b[m+ell] = Base(0); - z[m+ell] = Base(0); - for(k = 1; k < q; k++) - { b[m+ell] += Base(k) * b[(k-1)*r+1+ell] * b[(q-k-1)*r+1+ell]; - z[m+ell] += Base(k) * z[(k-1)*r+1+ell] * b[(q-k-1)*r+1+ell]; - } - b[m+ell] = ( uq / Base(2) - b[m+ell] / Base(q) ) / b[0]; - z[m+ell] = ( x[m+ell] - z[m+ell] / Base(q) ) / b[0]; - } -} - -/*! -Compute zero order forward mode Taylor coefficient for result of op = AsinhOp. - -The C++ source code corresponding to this operation is -\verbatim - z = asinh(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt( 1 + x * x ) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails forward_unary2_op_0 -*/ -template -inline void forward_asinh_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AsinhOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AsinhOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - Base* b = z - cap_order; // called y in documentation - - z[0] = asinh( x[0] ); - b[0] = sqrt( Base(1) + x[0] * x[0] ); -} -/*! -Compute reverse mode partial derivatives for result of op = AsinhOp. - -The C++ source code corresponding to this operation is -\verbatim - z = asinh(x) -\endverbatim -The auxillary result is -\verbatim - y = sqrt( 1 + x * x ) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails reverse_unary2_op -*/ - -template -inline void reverse_asinh_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AsinhOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AsinhOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to first result - const Base* z = taylor + i_z * cap_order; - Base* pz = partial + i_z * nc_partial; - - // Taylor coefficients and partials corresponding to auxillary result - const Base* b = z - cap_order; // called y in documentation - Base* pb = pz - nc_partial; - - Base inv_b0 = Base(1) / b[0]; - - // number of indices to access - size_t j = d; - size_t k; - while(j) - { - // scale partials w.r.t b[j] by 1 / b[0] - pb[j] = azmul(pb[j], inv_b0); - - // scale partials w.r.t z[j] by 1 / b[0] - pz[j] = azmul(pz[j], inv_b0); - - // update partials w.r.t b^0 - pb[0] -= azmul(pz[j], z[j]) + azmul(pb[j], b[j]); - - // update partial w.r.t. x^0 - px[0] += azmul(pb[j], x[j]); - - // update partial w.r.t. x^j - px[j] += pz[j] + azmul(pb[j], x[0]); - - // further scale partial w.r.t. z[j] by 1 / j - pz[j] /= Base(j); - - for(k = 1; k < j; k++) - { // update partials w.r.t b^(j-k) - pb[j-k] -= Base(k) * azmul(pz[j], z[k]) + azmul(pb[j], b[k]); - - // update partials w.r.t. x^k - px[k] += azmul(pb[j], x[j-k]); - - // update partials w.r.t. z^k - pz[k] -= Base(k) * azmul(pz[j], b[j-k]); - } - --j; - } - - // j == 0 case - px[0] += azmul(pz[0] + azmul(pb[0], x[0]), inv_b0); -} - -} // END_CPPAD_NAMESPACE -# endif -# endif diff --git a/ct_core/include/ct/external/cppad/local/atan2.hpp b/ct_core/include/ct/external/cppad/local/atan2.hpp deleted file mode 100644 index 9d87697db..000000000 --- a/ct_core/include/ct/external/cppad/local/atan2.hpp +++ /dev/null @@ -1,142 +0,0 @@ -// $Id: atan2.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_ATAN2_HPP -# define CPPAD_ATAN2_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin atan2$$ -$spell - Vec - CppAD - namespace - std - atan - const -$$ - - -$section AD Two Argument Inverse Tangent Function$$ -$mindex tan atan2$$ - -$head Syntax$$ -$icode%theta% = atan2(%y%, %x%)%$$ - - -$head Purpose$$ -Determines an angle $latex \theta \in [ - \pi , + \pi ]$$ -such that -$latex \[ -\begin{array}{rcl} - \sin ( \theta ) & = & y / \sqrt{ x^2 + y^2 } \\ - \cos ( \theta ) & = & x / \sqrt{ x^2 + y^2 } -\end{array} -\] $$ - -$head y$$ -The argument $icode y$$ has one of the following prototypes -$codei% - const AD<%Base%> &%y% - const VecAD<%Base%>::reference &%y% -%$$ - -$head x$$ -The argument $icode x$$ has one of the following prototypes -$codei% - const AD<%Base%> &%x% - const VecAD<%Base%>::reference &%x% -%$$ - -$head theta$$ -The result $icode theta$$ has prototype -$codei% - AD<%Base%> %theta% -%$$ - -$head Operation Sequence$$ -The AD of $icode Base$$ -operation sequence used to calculate $icode theta$$ is -$cref/independent/glossary/Operation/Independent/$$ -of $icode x$$ and $icode y$$. - -$head Example$$ -$children% - example/atan2.cpp -%$$ -The file -$cref atan2.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ - -namespace CppAD { // BEGIN CppAD namespace - -inline float atan2(float x, float y) -{ return std::atan2(x, y); } - -inline double atan2(double x, double y) -{ return std::atan2(x, y); } - -// The code below is used as an example by the CondExp documentation. -// BEGIN CondExp -template -AD atan2 (const AD &y, const AD &x) -{ AD alpha; - AD beta; - AD theta; - - AD zero(0.); - AD pi2(2. * atan(1.)); - AD pi(2. * pi2); - - AD ax = abs(x); - AD ay = abs(y); - - // if( ax > ay ) - // theta = atan(ay / ax); - // else theta = pi2 - atan(ax / ay); - alpha = atan(ay / ax); - beta = pi2 - atan(ax / ay); - theta = CondExpGt(ax, ay, alpha, beta); // use of CondExp - - // if( x <= 0 ) - // theta = pi - theta; - theta = CondExpLe(x, zero, pi - theta, theta); // use of CondExp - - // if( y <= 0 ) - // theta = - theta; - theta = CondExpLe(y, zero, -theta, theta); // use of CondExp - - return theta; -} -// END CondExp - -template -inline AD atan2 (const VecAD_reference &y, const AD &x) -{ return atan2( y.ADBase() , x ); } - -template -inline AD atan2 (const AD &y, const VecAD_reference &x) -{ return atan2( y , x.ADBase() ); } - -template -inline AD atan2 -(const VecAD_reference &y, const VecAD_reference &x) -{ return atan2( y.ADBase() , x.ADBase() ); } - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/atan_op.hpp b/ct_core/include/ct/external/cppad/local/atan_op.hpp deleted file mode 100644 index cb544e8d4..000000000 --- a/ct_core/include/ct/external/cppad/local/atan_op.hpp +++ /dev/null @@ -1,236 +0,0 @@ -// $Id: atan_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_ATAN_OP_HPP -# define CPPAD_ATAN_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file atan_op.hpp -Forward and reverse mode calculations for z = atan(x). -*/ - - -/*! -Forward mode Taylor coefficient for result of op = AtanOp. - -The C++ source code corresponding to this operation is -\verbatim - z = atan(x) -\endverbatim -The auxillary result is -\verbatim - y = 1 + x * x -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op -*/ -template -inline void forward_atan_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AtanOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AtanOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - Base* b = z - cap_order; // called y in documentation - - size_t k; - if( p == 0 ) - { z[0] = atan( x[0] ); - b[0] = Base(1) + x[0] * x[0]; - p++; - } - for(size_t j = p; j <= q; j++) - { - b[j] = Base(2) * x[0] * x[j]; - z[j] = Base(0); - for(k = 1; k < j; k++) - { b[j] += x[k] * x[j-k]; - z[j] -= Base(k) * z[k] * b[j-k]; - } - z[j] /= Base(j); - z[j] += x[j]; - z[j] /= b[0]; - } -} - -/*! -Multiple direction Taylor coefficient for op = AtanOp. - -The C++ source code corresponding to this operation is -\verbatim - z = atan(x) -\endverbatim -The auxillary result is -\verbatim - y = 1 + x * x -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op_dir -*/ -template -inline void forward_atan_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AtanOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AtanOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - Base* b = z - num_taylor_per_var; // called y in documentation - - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - { b[m+ell] = Base(2) * x[m+ell] * x[0]; - z[m+ell] = Base(q) * x[m+ell]; - for(size_t k = 1; k < q; k++) - { b[m+ell] += x[(k-1)*r+1+ell] * x[(q-k-1)*r+1+ell]; - z[m+ell] -= Base(k) * z[(k-1)*r+1+ell] * b[(q-k-1)*r+1+ell]; - } - z[m+ell] /= ( Base(q) * b[0] ); - } -} - -/*! -Zero order forward mode Taylor coefficient for result of op = AtanOp. - -The C++ source code corresponding to this operation is -\verbatim - z = atan(x) -\endverbatim -The auxillary result is -\verbatim - y = 1 + x * x -\endverbatim -The value of y is computed along with the value of z. - -\copydetails forward_unary2_op_0 -*/ -template -inline void forward_atan_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AtanOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AtanOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - Base* b = z - cap_order; // called y in documentation - - z[0] = atan( x[0] ); - b[0] = Base(1) + x[0] * x[0]; -} -/*! -Reverse mode partial derivatives for result of op = AtanOp. - -The C++ source code corresponding to this operation is -\verbatim - z = atan(x) -\endverbatim -The auxillary result is -\verbatim - y = 1 + x * x -\endverbatim -The value of y is computed along with the value of z. - -\copydetails reverse_unary2_op -*/ - -template -inline void reverse_atan_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AtanOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AtanOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to first result - const Base* z = taylor + i_z * cap_order; - Base* pz = partial + i_z * nc_partial; - - // Taylor coefficients and partials corresponding to auxillary result - const Base* b = z - cap_order; // called y in documentation - Base* pb = pz - nc_partial; - - Base inv_b0 = Base(1) / b[0]; - - // number of indices to access - size_t j = d; - size_t k; - while(j) - { // scale partials w.r.t z[j] and b[j] - pz[j] = azmul(pz[j], inv_b0); - pb[j] *= Base(2); - - pb[0] -= azmul(pz[j], z[j]); - px[j] += pz[j] + azmul(pb[j], x[0]); - px[0] += azmul(pb[j], x[j]); - - // more scaling of partials w.r.t z[j] - pz[j] /= Base(j); - - for(k = 1; k < j; k++) - { pb[j-k] -= Base(k) * azmul(pz[j], z[k]); - pz[k] -= Base(k) * azmul(pz[j], b[j-k]); - px[k] += azmul(pb[j], x[j-k]); - } - --j; - } - px[0] += azmul(pz[0], inv_b0) + Base(2) * azmul(pb[0], x[0]); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/atanh.hpp b/ct_core/include/ct/external/cppad/local/atanh.hpp deleted file mode 100644 index 9df0b3ef2..000000000 --- a/ct_core/include/ct/external/cppad/local/atanh.hpp +++ /dev/null @@ -1,97 +0,0 @@ -// $Id$ -# ifndef CPPAD_ATANH_HPP -# define CPPAD_ATANH_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin atanh$$ -$spell - atanh - const - Vec - std - cmath - CppAD - tanh -$$ -$section The Inverse Hyperbolic Tangent Function: atanh$$ - -$head Syntax$$ -$icode%y% = atanh(%x%)%$$ - -$head Description$$ -The inverse hyperbolic tangent function is defined by -$icode%x% == tanh(%y%)%$$. - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head CPPAD_USE_CPLUSPLUS_2011$$ - -$subhead true$$ -If this preprocessor symbol is true ($code 1$$), -and $icode x$$ is an AD type, -this is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$subhead false$$ -If this preprocessor symbol is false ($code 0$$), -CppAD uses the representation -$latex \[ -\R{atanh} (x) = \frac{1}{2} \log \left( \frac{1 + x}{1 - x} \right) -\] $$ -to compute this function. - -$head Example$$ -$children% - example/atanh.cpp -%$$ -The file -$cref atanh.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ -# include -# if ! CPPAD_USE_CPLUSPLUS_2011 - -// BEGIN CppAD namespace -namespace CppAD { - -template -Type atanh_template(const Type &x) -{ return CppAD::log( (1 + x) / (1 - x) ) / 2.0; -} - -inline float atanh(const float &x) -{ return atanh_template(x); } - -inline double atanh(const double &x) -{ return atanh_template(x); } - -template -inline AD atanh(const AD &x) -{ return atanh_template(x); } - -template -inline AD atanh(const VecAD_reference &x) -{ return atanh_template( x.ADBase() ); } - - -} // END CppAD namespace - -# endif // CPPAD_USE_CPLUSPLUS_2011 -# endif // CPPAD_ATANH_INCLUDED diff --git a/ct_core/include/ct/external/cppad/local/atanh_op.hpp b/ct_core/include/ct/external/cppad/local/atanh_op.hpp deleted file mode 100644 index 34639afeb..000000000 --- a/ct_core/include/ct/external/cppad/local/atanh_op.hpp +++ /dev/null @@ -1,238 +0,0 @@ -// $Id$ -# ifndef CPPAD_ATANH_OP_HPP -# define CPPAD_ATANH_OP_HPP -# if CPPAD_USE_CPLUSPLUS_2011 - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file atanh_op.hpp -Forward and reverse mode calculations for z = atanh(x). -*/ - - -/*! -Forward mode Taylor coefficient for result of op = AtanhOp. - -The C++ source code corresponding to this operation is -\verbatim - z = atanh(x) -\endverbatim -The auxillary result is -\verbatim - y = 1 - x * x -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op -*/ -template -inline void forward_atanh_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AtanhOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AtanhOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - Base* b = z - cap_order; // called y in documentation - - size_t k; - if( p == 0 ) - { z[0] = atanh( x[0] ); - b[0] = Base(1) - x[0] * x[0]; - p++; - } - for(size_t j = p; j <= q; j++) - { - b[j] = - Base(2) * x[0] * x[j]; - z[j] = Base(0); - for(k = 1; k < j; k++) - { b[j] -= x[k] * x[j-k]; - z[j] -= Base(k) * z[k] * b[j-k]; - } - z[j] /= Base(j); - z[j] += x[j]; - z[j] /= b[0]; - } -} - -/*! -Multiple direction Taylor coefficient for op = AtanhOp. - -The C++ source code corresponding to this operation is -\verbatim - z = atanh(x) -\endverbatim -The auxillary result is -\verbatim - y = 1 - x * x -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op_dir -*/ -template -inline void forward_atanh_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AtanhOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AtanhOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - Base* b = z - num_taylor_per_var; // called y in documentation - - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - { b[m+ell] = - Base(2) * x[m+ell] * x[0]; - z[m+ell] = Base(q) * x[m+ell]; - for(size_t k = 1; k < q; k++) - { b[m+ell] -= x[(k-1)*r+1+ell] * x[(q-k-1)*r+1+ell]; - z[m+ell] -= Base(k) * z[(k-1)*r+1+ell] * b[(q-k-1)*r+1+ell]; - } - z[m+ell] /= ( Base(q) * b[0] ); - } -} - -/*! -Zero order forward mode Taylor coefficient for result of op = AtanhOp. - -The C++ source code corresponding to this operation is -\verbatim - z = atanh(x) -\endverbatim -The auxillary result is -\verbatim - y = 1 - x * x -\endverbatim -The value of y is computed along with the value of z. - -\copydetails forward_unary2_op_0 -*/ -template -inline void forward_atanh_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AtanhOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AtanhOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - Base* b = z - cap_order; // called y in documentation - - z[0] = atanh( x[0] ); - b[0] = Base(1) - x[0] * x[0]; -} -/*! -Reverse mode partial derivatives for result of op = AtanhOp. - -The C++ source code corresponding to this operation is -\verbatim - z = atanh(x) -\endverbatim -The auxillary result is -\verbatim - y = 1 - x * x -\endverbatim -The value of y is computed along with the value of z. - -\copydetails reverse_unary2_op -*/ - -template -inline void reverse_atanh_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(AtanhOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(AtanhOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to first result - const Base* z = taylor + i_z * cap_order; - Base* pz = partial + i_z * nc_partial; - - // Taylor coefficients and partials corresponding to auxillary result - const Base* b = z - cap_order; // called y in documentation - Base* pb = pz - nc_partial; - - Base inv_b0 = Base(1) / b[0]; - - // number of indices to access - size_t j = d; - size_t k; - while(j) - { // scale partials w.r.t z[j] and b[j] - pz[j] = azmul(pz[j], inv_b0); - pb[j] *= Base(2); - - pb[0] -= azmul(pz[j], z[j]); - px[j] += pz[j] - azmul(pb[j], x[0]); - px[0] -= azmul(pb[j], x[j]); - - // more scaling of partials w.r.t z[j] - pz[j] /= Base(j); - - for(k = 1; k < j; k++) - { pb[j-k] -= Base(k) * azmul(pz[j], z[k]); - pz[k] -= Base(k) * azmul(pz[j], b[j-k]); - px[k] -= azmul(pb[j], x[j-k]); - } - --j; - } - px[0] += azmul(pz[0], inv_b0) - Base(2) * azmul(pb[0], x[0]); -} - -} // END_CPPAD_NAMESPACE -# endif -# endif diff --git a/ct_core/include/ct/external/cppad/local/atomic_base.hpp b/ct_core/include/ct/external/cppad/local/atomic_base.hpp deleted file mode 100644 index d7bd6bf8a..000000000 --- a/ct_core/include/ct/external/cppad/local/atomic_base.hpp +++ /dev/null @@ -1,1549 +0,0 @@ -// $Id: atomic_base.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_ATOMIC_BASE_HPP -# define CPPAD_ATOMIC_BASE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include -# include -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file atomic_base.hpp -Base class for atomic user operations. -*/ - -template -class atomic_base { -// =================================================================== -public: - enum option_enum { - pack_sparsity_enum , - bool_sparsity_enum , - set_sparsity_enum - }; -private: - // ------------------------------------------------------ - // constants - // - /// index of this object in class_object - const size_t index_; - - // ----------------------------------------------------- - // variables - // - /// sparsity pattern this object is currently using - /// (set by constructor and option member functions) - option_enum sparsity_; - - /// temporary work space used afun, declared here to avoid memory - /// allocation/deallocation for each call to afun - vector afun_vx_[CPPAD_MAX_NUM_THREADS]; - vector afun_vy_[CPPAD_MAX_NUM_THREADS]; - vector afun_tx_[CPPAD_MAX_NUM_THREADS]; - vector afun_ty_[CPPAD_MAX_NUM_THREADS]; - - // ----------------------------------------------------- - // static member functions - // - /// List of all the object in this class - static std::vector& class_object(void) - { CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static std::vector list_; - return list_; - } - /// List of names for each object in this class - static std::vector& class_name(void) - { CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static std::vector list_; - return list_; - } - // ===================================================================== -public: - // ----------------------------------------------------- - // member functions not in user API - // - /// current sparsity setting - option_enum sparsity(void) const - { return sparsity_; } - - /// Name corresponding to a base_atomic object - const std::string& afun_name(void) const - { return class_name()[index_]; } -/* -$begin atomic_ctor$$ -$spell - enum - sq - std - afun - arg - CppAD - bool - ctor - const - matrix_mul.hpp -$$ - -$section Atomic Function Constructor$$ - -$head Syntax$$ -$icode%atomic_user afun%(%ctor_arg_list%) -%$$ -$codei%atomic_base<%Base%>(%name%, %sparsity%) -%$$ - -$head atomic_user$$ - -$subhead ctor_arg_list$$ -Is a list of arguments for the $icode atomic_user$$ constructor. - -$subhead afun$$ -The object $icode afun$$ must stay in scope for as long -as the corresponding atomic function is used. -This includes use by any $cref/ADFun/ADFun/$$ that -has this $icode atomic_user$$ operation in its -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$subhead Implementation$$ -The user defined $icode atomic_user$$ class is a publicly derived class of -$codei%atomic_base<%Base%>%$$. -It should be declared as follows: -$codei% - class %atomic_user% : public CppAD::atomic_base<%Base%> { - public: - %atomic_user%(%ctor_arg_list%) : atomic_base<%Base%>(%name%, %sparsity%) - %...% - }; -%$$ -where $icode ...$$ -denotes the rest of the implementation of the derived class. -This includes completing the constructor and -all the virtual functions that have their -$code atomic_base$$ implementations replaced by -$icode atomic_user$$ implementations. - -$head atomic_base$$ - -$subhead Restrictions$$ -The $code atomic_base$$ constructor cannot be called in -$cref/parallel/ta_in_parallel/$$ mode. - -$subhead Base$$ -The template parameter determines the -$icode Base$$ type for this $codei%AD<%Base%>%$$ atomic operation. - -$subhead name$$ -This $code atomic_base$$ constructor argument has the following prototype -$codei% - const std::string& %name% -%$$ -It is the name for this atomic function and is used for error reporting. -The suggested value for $icode name$$ is $icode afun$$ or $icode atomic_user$$, -i.e., the name of the corresponding atomic object or class. - -$subhead sparsity$$ -This $code atomic_base$$ constructor argument has prototype -$codei% - atomic_base<%Base%>::option_enum %sparsity% -%$$ -The current $icode sparsity$$ for an $code atomic_base$$ object -determines which type of sparsity patterns it uses -and its value is one of the following: -$table -$icode sparsity$$ $cnext sparsity patterns $rnext -$codei%atomic_base<%Base%>::pack_sparsity_enum%$$ $pre $$ $cnext - $cref/vectorBool/CppAD_vector/vectorBool/$$ -$rnext -$codei%atomic_base<%Base%>::bool_sparsity_enum%$$ $pre $$ $cnext - $cref/vector/CppAD_vector/$$$code $$ -$rnext -$codei%atomic_base<%Base%>::set_sparsity_enum%$$ $pre $$ $cnext - $cref/vector/CppAD_vector/$$$code >$$ -$tend -There is a default value for $icode sparsity$$ if it is not -included in the constructor (which may be either the bool or set option). - -$head Examples$$ - -$subhead Define Constructor$$ -The following are links to user atomic function constructor definitions: -$cref%get_started.cpp%atomic_get_started.cpp%Constructor%$$, -$cref%norm_sq.cpp%atomic_norm_sq.cpp%Constructor%$$, -$cref%reciprocal.cpp%atomic_reciprocal.cpp%Constructor%$$, -$cref%tangent.cpp%atomic_tangent.cpp%Constructor%$$, -$cref%matrix_mul.hpp%atomic_matrix_mul.hpp%Constructor%$$. - -$subhead Use Constructor$$ -The following are links to user atomic function constructor uses: -$cref%get_started.cpp%atomic_get_started.cpp%Use Atomic Function%Constructor%$$, -$cref%norm_sq.cpp%atomic_norm_sq.cpp%Use Atomic Function%Constructor%$$, -$cref%reciprocal.cpp%atomic_reciprocal.cpp%Use Atomic Function%Constructor%$$, -$cref%tangent.cpp%atomic_tangent.cpp%Use Atomic Function%Constructor%$$, -$cref%mat_mul.cpp%atomic_mat_mul.cpp%Use Atomic Function%Constructor%$$. - - -$end -*/ -/*! -Base class for atomic_user functions. - -\tparam Base -This class is used for defining an AD atomic operation y = f(x). -*/ -/// make sure user does not invoke the default constructor -atomic_base(void) -{ CPPAD_ASSERT_KNOWN(false, - "Attempt to use the atomic_base default constructor" - ); -} -/*! -Constructor - -\param name -name used for error reporting - -\param sparsity [in] -what type of sparsity patterns are computed by this function, -bool_sparsity_enum or set_sparsity_enum. Default value is -bool sparsity patterns. -*/ -atomic_base( - const std::string& name, - option_enum sparsity = bool_sparsity_enum -) : -index_( class_object().size() ) , -sparsity_( sparsity ) -{ CPPAD_ASSERT_KNOWN( - ! thread_alloc::in_parallel() , - "atomic_base: constructor cannot be called in parallel mode." - ); - class_object().push_back(this); - class_name().push_back(name); - CPPAD_ASSERT_UNKNOWN( class_object().size() == class_name().size() ); -} -/// destructor informs CppAD that this atomic function with this index -/// has dropped out of scope by setting its pointer to null -virtual ~atomic_base(void) -{ CPPAD_ASSERT_UNKNOWN( class_object().size() > index_ ); - // change object pointer to null, but leave name for error reporting - class_object()[index_] = CPPAD_NULL; -} -/// atomic_base function object corresponding to a certain index -static atomic_base* class_object(size_t index) -{ CPPAD_ASSERT_UNKNOWN( class_object().size() > index ); - return class_object()[index]; -} -/// atomic_base function name corresponding to a certain index -static const std::string& class_name(size_t index) -{ CPPAD_ASSERT_UNKNOWN( class_name().size() > index ); - return class_name()[index]; -} -/* -$begin atomic_option$$ -$spell - sq - enum - afun - bool - CppAD - std - typedef -$$ - -$section Set Atomic Function Options$$ - -$head Syntax$$ -$icode%afun%.option(%option_value%)%$$ -These settings do not apply to individual $icode afun$$ calls, -but rather all subsequent uses of the corresponding atomic operation -in an $cref ADFun$$ object. - -$head atomic_sparsity$$ -Note that, if you use $cref optimize$$, these sparsity patterns are used -to determine the $cref/dependency/dependency.cpp/$$ relationship between -argument and result variables. - -$subhead pack_sparsity_enum$$ -If $icode option_value$$ is $codei%atomic_base<%Base%>::pack_sparsity_enum%$$, -then the type used by $icode afun$$ for -$cref/sparsity patterns/glossary/Sparsity Pattern/$$, -(after the option is set) will be -$codei% - typedef CppAD::vectorBool %atomic_sparsity% -%$$ -If $icode r$$ is a sparsity pattern -for a matrix $latex R \in B^{p \times q}$$: -$icode%r%.size() == %p% * %q%$$. - -$subhead bool_sparsity_enum$$ -If $icode option_value$$ is $codei%atomic_base<%Base%>::bool_sparsity_enum%$$, -then the type used by $icode afun$$ for -$cref/sparsity patterns/glossary/Sparsity Pattern/$$, -(after the option is set) will be -$codei% - typedef CppAD::vector %atomic_sparsity% -%$$ -If $icode r$$ is a sparsity pattern -for a matrix $latex R \in B^{p \times q}$$: -$icode%r%.size() == %p% * %q%$$. - -$subhead set_sparsity_enum$$ -If $icode option_value$$ is $icode%atomic_base<%Base%>::set_sparsity_enum%$$, -then the type used by $icode afun$$ for -$cref/sparsity patterns/glossary/Sparsity Pattern/$$, -(after the option is set) will be -$codei% - typedef CppAD::vector< std::set > %atomic_sparsity% -%$$ -If $icode r$$ is a sparsity pattern -for a matrix $latex R \in B^{p \times q}$$: -$icode%r%.size() == %p%$$, and for $latex i = 0 , \ldots , p-1$$, -the elements of $icode%r%[%i%]%$$ are between zero and $latex q-1$$ inclusive. - -$end -*/ -void option(enum option_enum option_value) -{ switch( option_value ) - { case pack_sparsity_enum: - case bool_sparsity_enum: - case set_sparsity_enum: - sparsity_ = option_value; - break; - - default: - CPPAD_ASSERT_KNOWN( - false, - "atoic_base::option: option_value is not valid" - ); - } - return; -} -/* ------------------------------------------------------------------------------ -$begin atomic_afun$$ - -$spell - sq - mul - afun - const - CppAD -$$ - -$section Using AD Version of Atomic Function$$ - -$head Syntax$$ -$icode%afun%(%ax%, %ay%)%$$ - -$head Purpose$$ -Given $icode ax$$, -this call computes the corresponding value of $icode ay$$. -If $codei%AD<%Base%>%$$ operations are being recorded, -it enters the computation as an atomic operation in the recording; -see $cref/start recording/Independent/Start Recording/$$. - -$head ADVector$$ -The type $icode ADVector$$ must be a -$cref/simple vector class/SimpleVector/$$ with elements of type -$codei%AD<%Base%>%$$; see $cref/Base/atomic_ctor/atomic_base/Base/$$. - -$head afun$$ -is a $cref/atomic_user/atomic_ctor/atomic_user/$$ object -and this $icode afun$$ function call is implemented by the -$cref/atomic_base/atomic_ctor/atomic_base/$$ class. - -$head ax$$ -This argument has prototype -$codei% - const %ADVector%& %ax% -%$$ -and size must be equal to $icode n$$. -It specifies vector $latex x \in B^n$$ -at which an $codei%AD<%Base%>%$$ version of -$latex y = f(x)$$ is to be evaluated; see -$cref/Base/atomic_ctor/atomic_base/Base/$$. - -$head ay$$ -This argument has prototype -$codei% - %ADVector%& %ay% -%$$ -and size must be equal to $icode m$$. -The input values of its elements -are not specified (must not matter). -Upon return, it is an $codei%AD<%Base%>%$$ version of -$latex y = f(x)$$. - -$head Examples$$ -The following files contain example uses of -the AD version of atomic functions during recording: -$cref%get_started.cpp%atomic_get_started.cpp%Use Atomic Function%Recording%$$, -$cref%norm_sq.cpp%atomic_norm_sq.cpp%Use Atomic Function%Recording%$$, -$cref%reciprocal.cpp%atomic_reciprocal.cpp%Use Atomic Function%Recording%$$, -$cref%tangent.cpp%atomic_tangent.cpp%Use Atomic Function%Recording%$$, -$cref%matrix_mul.cpp%atomic_mat_mul.cpp%Use Atomic Function%Recording%$$. - -$end ------------------------------------------------------------------------------ -*/ -/*! -Implement the user call to afun(ax, ay) and old_atomic call to -afun(ax, ay, id). - -\tparam ADVector -A simple vector class with elements of type AD. - -\param id -optional extra information vector that is just passed through by CppAD, -and used by old_atomic derived class (not other derived classes). -This is an extra parameter to the virtual callbacks for old_atomic; -see the set_id member function. - -\param ax -is the argument vector for this call, -ax.size() determines the number of arguments. - -\param ay -is the result vector for this call, -ay.size() determines the number of results. -*/ -template -void operator()( - const ADVector& ax , - ADVector& ay , - size_t id = 0 ) -{ size_t i, j; - size_t n = ax.size(); - size_t m = ay.size(); -# ifndef NDEBUG - bool ok; - std::string msg = "atomic_base: " + afun_name() + ".eval: "; - if( (n == 0) | (m == 0) ) - { msg += "ax.size() or ay.size() is zero"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - size_t thread = thread_alloc::thread_num(); - vector & tx = afun_tx_[thread]; - vector & ty = afun_ty_[thread]; - vector & vx = afun_vx_[thread]; - vector & vy = afun_vy_[thread]; - // - if( vx.size() != n ) - { vx.resize(n); - tx.resize(n); - } - if( vy.size() != m ) - { vy.resize(m); - ty.resize(m); - } - // - // Determine tape corresponding to variables in ax - tape_id_t tape_id = 0; - ADTape* tape = CPPAD_NULL; - for(j = 0; j < n; j++) - { tx[j] = ax[j].value_; - vx[j] = Variable( ax[j] ); - if( vx[j] ) - { - if( tape_id == 0 ) - { tape = ax[j].tape_this(); - tape_id = ax[j].tape_id_; - CPPAD_ASSERT_UNKNOWN( tape != CPPAD_NULL ); - } -# ifndef NDEBUG - if( tape_id != ax[j].tape_id_ ) - { msg += afun_name() + - ": ax contains variables from different threads."; - CPPAD_ASSERT_KNOWN(false, msg.c_str()); - } -# endif - } - } - // Use zero order forward mode to compute values - size_t p = 0, q = 0; - set_id(id); -# ifdef NDEBUG - forward(p, q, vx, vy, tx, ty); -# else - ok = forward(p, q, vx, vy, tx, ty); - if( ! ok ) - { msg += afun_name() + ": ok is false for " - "zero order forward mode calculation."; - CPPAD_ASSERT_KNOWN(false, msg.c_str()); - } -# endif - bool record_operation = false; - for(i = 0; i < m; i++) - { - // pass back values - ay[i].value_ = ty[i]; - - // initialize entire vector parameters (not in tape) - ay[i].tape_id_ = 0; - ay[i].taddr_ = 0; - - // we need to record this operation if - // any of the eleemnts of ay are variables, - record_operation |= vy[i]; - } -# ifndef NDEBUG - if( record_operation & (tape == CPPAD_NULL) ) - { msg += - "all elements of vx are false but vy contains a true element"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - // if tape is not null, ay is on the tape - if( record_operation ) - { - // Operator that marks beginning of this atomic operation - CPPAD_ASSERT_UNKNOWN( NumRes(UserOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( NumArg(UserOp) == 4 ); - tape->Rec_.PutArg(index_, id, n, m); - tape->Rec_.PutOp(UserOp); - - // Now put n operators, one for each element of argument vector - CPPAD_ASSERT_UNKNOWN( NumRes(UsravOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( NumRes(UsrapOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( NumArg(UsravOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(UsrapOp) == 1 ); - for(j = 0; j < n; j++) - { if( vx[j] ) - { // information for an argument that is a variable - tape->Rec_.PutArg(ax[j].taddr_); - tape->Rec_.PutOp(UsravOp); - } - else - { // information for an argument that is parameter - addr_t par = tape->Rec_.PutPar(ax[j].value_); - tape->Rec_.PutArg(par); - tape->Rec_.PutOp(UsrapOp); - } - } - - // Now put m operators, one for each element of result vector - CPPAD_ASSERT_UNKNOWN( NumArg(UsrrpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(UsrrpOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( NumArg(UsrrvOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( NumRes(UsrrvOp) == 1 ); - for(i = 0; i < m; i++) - { if( vy[i] ) - { ay[i].taddr_ = tape->Rec_.PutOp(UsrrvOp); - ay[i].tape_id_ = tape_id; - } - else - { addr_t par = tape->Rec_.PutPar(ay[i].value_); - tape->Rec_.PutArg(par); - tape->Rec_.PutOp(UsrrpOp); - } - } - - // Put a duplicate UserOp at end of UserOp sequence - tape->Rec_.PutArg(index_, id, n, m); - tape->Rec_.PutOp(UserOp); - } - return; -} -/* ------------------------------------------------------------------------------ -$begin atomic_forward$$ -$spell - sq - mul.hpp - hes - afun - vx - vy - ty - Taylor - const - CppAD - bool -$$ - -$section Atomic Forward Mode$$ -$mindex callback virtual$$ - - -$head Syntax$$ -$icode%ok% = %afun%.forward(%p%, %q%, %vx%, %vy%, %tx%, %ty%)%$$ - -$head Purpose$$ -This virtual function is used by $cref atomic_afun$$ -to evaluate function values. -It is also used buy $cref/forward/Forward/$$ -to compute function vales and derivatives. - -$head Implementation$$ -This virtual function must be defined by the -$cref/atomic_user/atomic_ctor/atomic_user/$$ class. -It can just return $icode%ok% == false%$$ -(and not compute anything) for values -of $icode%q% > 0%$$ that are greater than those used by your -$cref/forward/Forward/$$ mode calculations. - -$head p$$ -The argument $icode p$$ has prototype -$codei% - size_t %p% -%$$ -It specifies the lowest order Taylor coefficient that we are evaluating. -During calls to $cref atomic_afun$$, $icode%p% == 0%$$. - -$head q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the highest order Taylor coefficient that we are evaluating. -During calls to $cref atomic_afun$$, $icode%q% == 0%$$. - -$head vx$$ -The $code forward$$ argument $icode vx$$ has prototype -$codei% - const CppAD::vector& %vx% -%$$ -The case $icode%vx%.size() > 0%$$ only occurs while evaluating a call to -$cref atomic_afun$$. -In this case, -$icode%p% == %q% == 0%$$, -$icode%vx%.size() == %n%$$, and -for $latex j = 0 , \ldots , n-1$$, -$icode%vx%[%j%]%$$ is true if and only if -$icode%ax%[%j%]%$$ is a $cref/variable/glossary/Variable/$$ -in the corresponding call to -$codei% - %afun%(%ax%, %ay%, %id%) -%$$ -If $icode%vx%.size() == 0%$$, -then $icode%vy%.size() == 0%$$ and neither of these vectors -should be used. - -$head vy$$ -The $code forward$$ argument $icode vy$$ has prototype -$codei% - CppAD::vector& %vy% -%$$ -If $icode%vy%.size() == 0%$$, it should not be used. -Otherwise, -$icode%q% == 0%$$ and $icode%vy%.size() == %m%$$. -The input values of the elements of $icode vy$$ -are not specified (must not matter). -Upon return, for $latex j = 0 , \ldots , m-1$$, -$icode%vy%[%i%]%$$ is true if and only if -$icode%ay%[%i%]%$$ is a variable -(CppAD uses $icode vy$$ to reduce the necessary computations). - -$head tx$$ -The argument $icode tx$$ has prototype -$codei% - const CppAD::vector<%Base%>& %tx% -%$$ -and $icode%tx%.size() == (%q%+1)*%n%$$. -For $latex j = 0 , \ldots , n-1$$ and $latex k = 0 , \ldots , q$$, -we use the Taylor coefficient notation -$latex \[ -\begin{array}{rcl} - x_j^k & = & tx [ j * ( q + 1 ) + k ] - \\ - X_j (t) & = & x_j^0 + x_j^1 t^1 + \cdots + x_j^q t^q -\end{array} -\] $$ -Note that superscripts represent an index for $latex x_j^k$$ -and an exponent for $latex t^k$$. -Also note that the Taylor coefficients for $latex X(t)$$ correspond -to the derivatives of $latex X(t)$$ at $latex t = 0$$ in the following way: -$latex \[ - x_j^k = \frac{1}{ k ! } X_j^{(k)} (0) -\] $$ - -$head ty$$ -The argument $icode ty$$ has prototype -$codei% - CppAD::vector<%Base%>& %ty% -%$$ -and $icode%tx%.size() == (%q%+1)*%m%$$. -Upon return, -For $latex i = 0 , \ldots , m-1$$ and $latex k = 0 , \ldots , q$$, -$latex \[ -\begin{array}{rcl} - Y_i (t) & = & f_i [ X(t) ] - \\ - Y_i (t) & = & y_i^0 + y_i^1 t^1 + \cdots + y_i^q t^q + o ( t^q ) - \\ - ty [ i * ( q + 1 ) + k ] & = & y_i^k -\end{array} -\] $$ -where $latex o( t^q ) / t^q \rightarrow 0$$ as $latex t \rightarrow 0$$. -Note that superscripts represent an index for $latex y_j^k$$ -and an exponent for $latex t^k$$. -Also note that the Taylor coefficients for $latex Y(t)$$ correspond -to the derivatives of $latex Y(t)$$ at $latex t = 0$$ in the following way: -$latex \[ - y_j^k = \frac{1}{ k ! } Y_j^{(k)} (0) -\] $$ -If $latex p > 0$$, -for $latex i = 0 , \ldots , m-1$$ and $latex k = 0 , \ldots , p-1$$, -the input of $icode ty$$ satisfies -$latex \[ - ty [ i * ( q + 1 ) + k ] = y_i^k -\]$$ -and hence the corresponding elements need not be recalculated. - -$head ok$$ -If the required results are calculated, $icode ok$$ should be true. -Otherwise, it should be false. - -$head Discussion$$ -For example, suppose that $icode%q% == 2%$$, -and you know how to compute the function $latex f(x)$$, -its first derivative $latex f^{(1)} (x)$$, -and it component wise Hessian $latex f_i^{(2)} (x)$$. -Then you can compute $icode ty$$ using the following formulas: -$latex \[ -\begin{array}{rcl} -y_i^0 & = & Y(0) - = f_i ( x^0 ) -\\ -y_i^1 & = & Y^{(1)} ( 0 ) - = f_i^{(1)} ( x^0 ) X^{(1)} ( 0 ) - = f_i^{(1)} ( x^0 ) x^1 -\\ -y_i^2 -& = & \frac{1}{2 !} Y^{(2)} (0) -\\ -& = & \frac{1}{2} X^{(1)} (0)^\R{T} f_i^{(2)} ( x^0 ) X^{(1)} ( 0 ) - + \frac{1}{2} f_i^{(1)} ( x^0 ) X^{(2)} ( 0 ) -\\ -& = & \frac{1}{2} (x^1)^\R{T} f_i^{(2)} ( x^0 ) x^1 - + f_i^{(1)} ( x^0 ) x^2 -\end{array} -\] $$ -For $latex i = 0 , \ldots , m-1$$, and $latex k = 0 , 1 , 2$$, -$latex \[ - ty [ i * (q + 1) + k ] = y_i^k -\] $$ - -$head Examples$$ - -$subhead Define forward$$ -The following files contain example atomic $code forward$$ functions: -$cref%get_started.cpp%atomic_get_started.cpp%forward%$$, -$cref%norm_sq.cpp%atomic_norm_sq.cpp%forward%$$, -$cref%reciprocal.cpp%atomic_reciprocal.cpp%forward%$$, -$cref%tangent.cpp%atomic_tangent.cpp%forward%$$, -$cref%matrix_mul.hpp%atomic_matrix_mul.hpp%forward%$$. - -$subhead Use forward$$ -The following are links to user atomic function forward uses: -$cref%get_started.cpp%atomic_get_started.cpp%Use Atomic Function%forward%$$, -$cref%norm_sq.cpp%atomic_norm_sq.cpp%Use Atomic Function%forward%$$, -$cref%reciprocal.cpp%atomic_reciprocal.cpp%Use Atomic Function%forward%$$, -$cref%tangent.cpp%atomic_tangent.cpp%Use Atomic Function%forward%$$, -$cref%mat_mul.cpp%atomic_mat_mul.cpp%Use Atomic Function%forward%$$. - - -$end ------------------------------------------------------------------------------ -*/ -/*! -Link from atomic_base to forward mode - -\param p [in] -lowerest order for this forward mode calculation. - -\param q [in] -highest order for this forward mode calculation. - -\param vx [in] -if size not zero, which components of \c x are variables - -\param vy [out] -if size not zero, which components of \c y are variables - -\param tx [in] -Taylor coefficients corresponding to \c x for this calculation. - -\param ty [out] -Taylor coefficient corresponding to \c y for this calculation - -See the forward mode in user's documentation for base_atomic -*/ -virtual bool forward( - size_t p , - size_t q , - const vector& vx , - vector& vy , - const vector& tx , - vector& ty ) -{ return false; } -/* ------------------------------------------------------------------------------ -$begin atomic_reverse$$ -$spell - sq - mul.hpp - afun - ty - px - py - Taylor - const - CppAD -$$ - -$section Atomic Reverse Mode$$ -$spell - bool -$$ - -$head Syntax$$ -$icode%ok% = %afun%.reverse(%q%, %tx%, %ty%, %px%, %py%)%$$ - -$head Purpose$$ -This function is used by $cref/reverse/Reverse/$$ -to compute derivatives. - -$head Implementation$$ -If you are using -$cref/reverse/Reverse/$$ mode, -this virtual function must be defined by the -$cref/atomic_user/atomic_ctor/atomic_user/$$ class. -It can just return $icode%ok% == false%$$ -(and not compute anything) for values -of $icode q$$ that are greater than those used by your -$cref/reverse/Reverse/$$ mode calculations. - -$head q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the highest order Taylor coefficient that -computing the derivative of. - -$head tx$$ -The argument $icode tx$$ has prototype -$codei% - const CppAD::vector<%Base%>& %tx% -%$$ -and $icode%tx%.size() == (%q%+1)*%n%$$. -For $latex j = 0 , \ldots , n-1$$ and $latex k = 0 , \ldots , q$$, -we use the Taylor coefficient notation -$latex \[ -\begin{array}{rcl} - x_j^k & = & tx [ j * ( q + 1 ) + k ] - \\ - X_j (t) & = & x_j^0 + x_j^1 t^1 + \cdots + x_j^q t^q -\end{array} -\] $$ -Note that superscripts represent an index for $latex x_j^k$$ -and an exponent for $latex t^k$$. -Also note that the Taylor coefficients for $latex X(t)$$ correspond -to the derivatives of $latex X(t)$$ at $latex t = 0$$ in the following way: -$latex \[ - x_j^k = \frac{1}{ k ! } X_j^{(k)} (0) -\] $$ - -$head ty$$ -The argument $icode ty$$ has prototype -$codei% - const CppAD::vector<%Base%>& %ty% -%$$ -and $icode%tx%.size() == (%q%+1)*%m%$$. -For $latex i = 0 , \ldots , m-1$$ and $latex k = 0 , \ldots , q$$, -we use the Taylor coefficient notation -$latex \[ -\begin{array}{rcl} - Y_i (t) & = & f_i [ X(t) ] - \\ - Y_i (t) & = & y_i^0 + y_i^1 t^1 + \cdots + y_i^q t^q + o ( t^q ) - \\ - y_i^k & = & ty [ i * ( q + 1 ) + k ] -\end{array} -\] $$ -where $latex o( t^q ) / t^q \rightarrow 0$$ as $latex t \rightarrow 0$$. -Note that superscripts represent an index for $latex y_j^k$$ -and an exponent for $latex t^k$$. -Also note that the Taylor coefficients for $latex Y(t)$$ correspond -to the derivatives of $latex Y(t)$$ at $latex t = 0$$ in the following way: -$latex \[ - y_j^k = \frac{1}{ k ! } Y_j^{(k)} (0) -\] $$ - - -$head F, G, H$$ -We use the notation $latex \{ x_j^k \} \in B^{n \times (q+1)}$$ for -$latex \[ - \{ x_j^k \W{:} j = 0 , \ldots , n-1, k = 0 , \ldots , q \} -\]$$ -We use the notation $latex \{ y_i^k \} \in B^{m \times (q+1)}$$ for -$latex \[ - \{ y_i^k \W{:} i = 0 , \ldots , m-1, k = 0 , \ldots , q \} -\]$$ -We define the function -$latex F : B^{n \times (q+1)} \rightarrow B^{m \times (q+1)}$$ by -$latex \[ - y_i^k = F_i^k [ \{ x_j^k \} ] -\] $$ -We use $latex G : B^{m \times (q+1)} \rightarrow B$$ -to denote an arbitrary scalar valued function of $latex \{ y_i^k \}$$. -We use $latex H : B^{n \times (q+1)} \rightarrow B$$ -defined by -$latex \[ - H ( \{ x_j^k \} ) = G[ F( \{ x_j^k \} ) ] -\] $$ - -$head py$$ -The argument $icode py$$ has prototype -$codei% - const CppAD::vector<%Base%>& %py% -%$$ -and $icode%py%.size() == m * (%q%+1)%$$. -For $latex i = 0 , \ldots , m-1$$, $latex k = 0 , \ldots , q$$, -$latex \[ - py[ i * (q + 1 ) + k ] = \partial G / \partial y_i^k -\] $$ - -$subhead px$$ -The $icode px$$ has prototype -$codei% - CppAD::vector<%Base%>& %px% -%$$ -and $icode%px%.size() == n * (%q%+1)%$$. -The input values of the elements of $icode px$$ -are not specified (must not matter). -Upon return, -for $latex j = 0 , \ldots , n-1$$ and $latex \ell = 0 , \ldots , q$$, -$latex \[ -\begin{array}{rcl} -px [ j * (q + 1) + \ell ] & = & \partial H / \partial x_j^\ell -\\ -& = & -( \partial G / \partial \{ y_i^k \} ) - ( \partial \{ y_i^k \} / \partial x_j^\ell ) -\\ -& = & -\sum_{i=0}^{m-1} \sum_{k=0}^q -( \partial G / \partial y_i^k ) ( \partial y_i^k / \partial x_j^\ell ) -\\ -& = & -\sum_{i=0}^{m-1} \sum_{k=\ell}^q -py[ i * (q + 1 ) + k ] ( \partial F_i^k / \partial x_j^\ell ) -\end{array} -\] $$ -Note that we have used the fact that for $latex k < \ell$$, -$latex \partial F_i^k / \partial x_j^\ell = 0$$. - -$head ok$$ -The return value $icode ok$$ has prototype -$codei% - bool %ok% -%$$ -If it is $code true$$, the corresponding evaluation succeeded, -otherwise it failed. - -$head Examples$$ - -$subhead Define reverse$$ -The following files contain example atomic $code reverse$$ functions: -$cref%norm_sq.cpp%atomic_norm_sq.cpp%reverse%$$, -$cref%reciprocal.cpp%atomic_reciprocal.cpp%reverse%$$, -$cref%tangent.cpp%atomic_tangent.cpp%reverse%$$, -$cref%matrix_mul.hpp%atomic_matrix_mul.hpp%reverse%$$. - -$subhead Use reverse$$ -The following are links to user atomic function constructor uses: -$cref%norm_sq.cpp%atomic_norm_sq.cpp%Use Atomic Function%reverse%$$, -$cref%reciprocal.cpp%atomic_reciprocal.cpp%Use Atomic Function%reverse%$$, -$cref%tangent.cpp%atomic_tangent.cpp%Use Atomic Function%reverse%$$, -$cref%mat_mul.cpp%atomic_mat_mul.cpp%Use Atomic Function%reverse%$$. - -$end ------------------------------------------------------------------------------ -*/ -/*! -Link from reverse mode sweep to users routine. - -\param q [in] -highest order for this reverse mode calculation. - -\param tx [in] -Taylor coefficients corresponding to \c x for this calculation. - -\param ty [in] -Taylor coefficient corresponding to \c y for this calculation - -\param px [out] -Partials w.r.t. the \c x Taylor coefficients. - -\param py [in] -Partials w.r.t. the \c y Taylor coefficients. - -See atomic_reverse mode use documentation -*/ -virtual bool reverse( - size_t q , - const vector& tx , - const vector& ty , - vector& px , - const vector& py ) -{ return false; } -/* --------------------------------------- --------------------------------------- -$begin atomic_for_sparse_jac$$ -$spell - sq - mul.hpp - afun - Jacobian - jac - const - CppAD - std - bool - std -$$ - -$section Atomic Forward Jacobian Sparsity Patterns$$ - -$head Syntax$$ -$icode%ok% = %afun%.for_sparse_jac(%q%, %r%, %s%)%$$ - -$head Purpose$$ -This function is used by $cref ForSparseJac$$ to compute -Jacobian sparsity patterns. -For a fixed matrix $latex R \in B^{n \times q}$$, -the Jacobian of $latex f( x + R * u)$$ with respect to $latex u \in B^q$$ is -$latex \[ - S(x) = f^{(1)} (x) * R -\] $$ -Given a $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for $latex R$$, -$code for_sparse_jac$$ computes a sparsity pattern for $latex S(x)$$. - -$head Implementation$$ -If you are using $cref ForSparseJac$$, -this virtual function must be defined by the -$cref/atomic_user/atomic_ctor/atomic_user/$$ class. - -$subhead q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of columns in -$latex R \in B^{n \times q}$$ and the Jacobian -$latex S(x) \in B^{m \times q}$$. - -$subhead r$$ -This argument has prototype -$codei% - const %atomic_sparsity%& %r% -%$$ -and is a $cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -$latex R \in B^{n \times q}$$. - -$subhead s$$ -This argument has prototype -$codei% - %atomic_sparsity%& %s% -%$$ -The input values of its elements -are not specified (must not matter). -Upon return, $icode s$$ is a -$cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -$latex S(x) \in B^{m \times q}$$. - -$head ok$$ -The return value $icode ok$$ has prototype -$codei% - bool %ok% -%$$ -If it is $code true$$, the corresponding evaluation succeeded, -otherwise it failed. - -$head Examples$$ - -$subhead Define for_sparse_jac$$ -The following files contain example atomic $code for_sparse_jac$$ functions: -$cref%norm_sq.cpp%atomic_norm_sq.cpp%for_sparse_jac%$$, -$cref%reciprocal.cpp%atomic_reciprocal.cpp%for_sparse_jac%$$, -$cref%tangent.cpp%atomic_tangent.cpp%for_sparse_jac%$$, -$cref%matrix_mul.hpp%atomic_matrix_mul.hpp%for_sparse_jac%$$. - -$subhead Use for_sparse_jac$$ -The following are links to user atomic function constructor uses: -$cref%norm_sq.cpp% - atomic_norm_sq.cpp%Use Atomic Function%for_sparse_jac%$$, -$cref%reciprocal.cpp% - atomic_reciprocal.cpp%Use Atomic Function%for_sparse_jac%$$, -$cref%tangent.cpp%atomic_tangent.cpp%Use Atomic Function%for_sparse_jac%$$, -$cref%mat_mul.cpp%atomic_mat_mul.cpp%Use Atomic Function%for_sparse_jac%$$. - -$end ------------------------------------------------------------------------------ -*/ -/*! -Link from forward Jacobian sparsity sweep to atomic_base - -\param q -is the column dimension for the Jacobian sparsity partterns. - -\param r -is the Jacobian sparsity pattern for the argument vector x - -\param s -is the Jacobian sparsity pattern for the result vector y -*/ -virtual bool for_sparse_jac( - size_t q , - const vector< std::set >& r , - vector< std::set >& s ) -{ return false; } -virtual bool for_sparse_jac( - size_t q , - const vector& r , - vector& s ) -{ return false; } -virtual bool for_sparse_jac( - size_t q , - const vectorBool& r , - vectorBool& s ) -{ return false; } -/* --------------------------------------- --------------------------------------- -$begin atomic_rev_sparse_jac$$ -$spell - sq - mul.hpp - rt - afun - Jacobian - jac - CppAD - std - bool - const - hes -$$ - -$section Atomic Reverse Jacobian Sparsity Patterns$$ - -$head Syntax$$ -$icode%ok% = %afun%.rev_sparse_jac(%q%, %rt%, %st%)%$$ - -$head Purpose$$ -This function is used by $cref RevSparseJac$$ to compute -Jacobian sparsity patterns. -For a fixed matrix $latex R \in B^{q \times m}$$, -the Jacobian of $latex R * f( x )$$ with respect to $latex x \in B^q$$ is -$latex \[ - S(x) = R * f^{(1)} (x) -\] $$ -Given a $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for $latex R$$, -$code rev_sparse_jac$$ computes a sparsity pattern for $latex S(x)$$. - -$head Implementation$$ -If you are using $cref RevSparseJac$$, -this virtual function must be defined by the -$cref/atomic_user/atomic_ctor/atomic_user/$$ class. - -$subhead q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of rows in -$latex R \in B^{q \times m}$$ and the Jacobian -$latex S(x) \in B^{q \times n}$$. - -$subhead rt$$ -This argument has prototype -$codei% - const %atomic_sparsity%& %rt% -%$$ -and is a -$cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -$latex R^\R{T} \in B^{m \times q}$$. - -$subhead st$$ -This argument has prototype -$codei% - %atomic_sparsity%& %st% -%$$ -The input value of its elements -are not specified (must not matter). -Upon return, $icode s$$ is a -$cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -$latex S(x)^\R{T} \in B^{n \times q}$$. - -$head ok$$ -The return value $icode ok$$ has prototype -$codei% - bool %ok% -%$$ -If it is $code true$$, the corresponding evaluation succeeded, -otherwise it failed. - -$head Examples$$ - -$subhead Define rev_sparse_jac$$ -The following files contain example atomic $code rev_sparse_jac$$ functions: -$cref%norm_sq.cpp%atomic_norm_sq.cpp%rev_sparse_jac%$$, -$cref%reciprocal.cpp%atomic_reciprocal.cpp%rev_sparse_jac%$$, -$cref%tangent.cpp%atomic_tangent.cpp%rev_sparse_jac%$$, -$cref%matrix_mul.hpp%atomic_matrix_mul.hpp%rev_sparse_jac%$$. - -$subhead Use rev_sparse_jac$$ -The following are links to user atomic function constructor uses: -$cref%norm_sq.cpp% - atomic_norm_sq.cpp%Use Atomic Function%rev_sparse_jac%$$, -$cref%reciprocal.cpp% - atomic_reciprocal.cpp%Use Atomic Function%rev_sparse_jac%$$, -$cref%tangent.cpp%atomic_tangent.cpp%Use Atomic Function%rev_sparse_jac%$$, -$cref%mat_mul.cpp%atomic_mat_mul.cpp%Use Atomic Function%rev_sparse_jac%$$. - -$end ------------------------------------------------------------------------------ -*/ -/*! -Link from reverse Jacobian sparsity sweep to atomic_base - -\param q [in] -is the row dimension for the Jacobian sparsity partterns - -\param rt [out] -is the tansposed Jacobian sparsity pattern w.r.t to range variables y - -\param st [in] -is the tansposed Jacobian sparsity pattern for the argument variables x -*/ -virtual bool rev_sparse_jac( - size_t q , - const vector< std::set >& rt , - vector< std::set >& st ) -{ return false; } -virtual bool rev_sparse_jac( - size_t q , - const vector& rt , - vector& st ) -{ return false; } -virtual bool rev_sparse_jac( - size_t q , - const vectorBool& rt , - vectorBool& st ) -{ return false; } -/* --------------------------------------- --------------------------------------- -$begin atomic_rev_sparse_hes$$ -$spell - sq - mul.hpp - vx - afun - Jacobian - jac - CppAD - std - bool - hes - const -$$ - -$section Atomic Reverse Hessian Sparsity Patterns$$ - -$head Syntax$$ -$icode%ok% = %afun%.rev_sparse_hes(%vx%, %s%, %t%, %q%, %r%, %u%, %v%)%$$ - -$head Purpose$$ -This function is used by $cref RevSparseHes$$ to compute -Hessian sparsity patterns. -There is an unspecified scalar valued function -$latex g : B^m \rightarrow B$$. -Given a $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for -$latex R \in B^{n \times q}$$, -and information about the function $latex z = g(y)$$, -this routine computes the sparsity pattern for -$latex \[ - V(x) = (g \circ f)^{(2)}( x ) R -\] $$ - -$head Implementation$$ -If you are using and $cref RevSparseHes$$, -this virtual function must be defined by the -$cref/atomic_user/atomic_ctor/atomic_user/$$ class. - -$subhead vx$$ -The argument $icode vx$$ has prototype -$codei% - const CppAD:vector& %vx% -%$$ -$icode%vx%.size() == %n%$$, and -for $latex j = 0 , \ldots , n-1$$, -$icode%vx%[%j%]%$$ is true if and only if -$icode%ax%[%j%]%$$ is a $cref/variable/glossary/Variable/$$ -in the corresponding call to -$codei% - %afun%(%ax%, %ay%, %id%) -%$$ - -$subhead s$$ -The argument $icode s$$ has prototype -$codei% - const CppAD:vector& %s% -%$$ -and its size is $icode m$$. -It is a sparsity pattern for -$latex S(x) = g^{(1)} (y) \in B^{1 \times m}$$. - -$subhead t$$ -This argument has prototype -$codei% - CppAD:vector& %t% -%$$ -and its size is $icode m$$. -The input values of its elements -are not specified (must not matter). -Upon return, $icode t$$ is a -sparsity pattern for -$latex T(x) \in B^{1 \times n}$$ where -$latex \[ - T(x) = (g \circ f)^{(1)} (x) = S(x) * f^{(1)} (x) -\]$$ - -$subhead q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of columns in -$latex R \in B^{n \times q}$$, -$latex U(x) \in B^{m \times q}$$, and -$latex V(x) \in B^{n \times q}$$. - -$subhead r$$ -This argument has prototype -$codei% - const %atomic_sparsity%& %r% -%$$ -and is a $cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -$latex R \in B^{n \times q}$$. - -$head u$$ -This argument has prototype -$codei% - const %atomic_sparsity%& %u% -%$$ -and is a $cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -$latex U(x) \in B^{m \times q}$$ which is defined by -$latex \[ -\begin{array}{rcl} -U(x) -& = & -\partial_u \{ \partial_y g[ y + f^{(1)} (x) R u ] \}_{u=0} -\\ -& = & -\partial_u \{ g^{(1)} [ y + f^{(1)} (x) R u ] \}_{u=0} -\\ -& = & -g^{(2)} (y) f^{(1)} (x) R -\end{array} -\] $$ - -$subhead v$$ -This argument has prototype -$codei% - %atomic_sparsity%& %v% -%$$ -The input value of its elements -are not specified (must not matter). -Upon return, $icode v$$ is a -$cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ pattern for -$latex V(x) \in B^{n \times q}$$ which is defined by -$latex \[ -\begin{array}{rcl} -V(x) -& = & -\partial_u [ \partial_x (g \circ f) ( x + R u ) ]_{u=0} -\\ -& = & -\partial_u [ (g \circ f)^{(1)}( x + R u ) ]_{u=0} -\\ -& = & -(g \circ f)^{(2)}( x ) R -\\ -& = & -f^{(1)} (x)^\R{T} g^{(2)} ( y ) f^{(1)} (x) R -+ -\sum_{i=1}^m g_i^{(1)} (y) \; f_i^{(2)} (x) R -\\ -& = & -f^{(1)} (x)^\R{T} U(x) -+ -\sum_{i=1}^m S_i (x) \; f_i^{(2)} (x) R -\end{array} -\] $$ - -$head Examples$$ - -$subhead Define rev_sparse_hes$$ -The following files contain example atomic $code rev_sparse_hes$$ functions: -$cref%norm_sq.cpp%atomic_norm_sq.cpp%rev_sparse_hes%$$, -$cref%reciprocal.cpp%atomic_reciprocal.cpp%rev_sparse_hes%$$, -$cref%tangent.cpp%atomic_tangent.cpp%rev_sparse_hes%$$, -$cref%matrix_mul.hpp%atomic_matrix_mul.hpp%rev_sparse_hes%$$. - -$subhead Use rev_sparse_hes$$ -The following are links to user atomic function constructor uses: -$cref%norm_sq.cpp% - atomic_norm_sq.cpp%Use Atomic Function%rev_sparse_hes%$$, -$cref%reciprocal.cpp% - atomic_reciprocal.cpp%Use Atomic Function%rev_sparse_hes%$$, -$cref%tangent.cpp%atomic_tangent.cpp%Use Atomic Function%rev_sparse_hes%$$, -$cref%mat_mul.cpp%atomic_mat_mul.cpp%Use Atomic Function%rev_sparse_hes%$$. - -$end ------------------------------------------------------------------------------ -*/ -/*! -Link from reverse Hessian sparsity sweep to base_atomic - -\param vx [in] -which componens of x are variables. - -\param s [in] -is the reverse Jacobian sparsity pattern w.r.t the result vector y. - -\param t [out] -is the reverse Jacobian sparsity pattern w.r.t the argument vector x. - -\param q [in] -is the column dimension for the sparsity partterns. - -\param r [in] -is the forward Jacobian sparsity pattern w.r.t the argument vector x - -\param u [in] -is the Hessian sparsity pattern w.r.t the result vector y. - -\param v [out] -is the Hessian sparsity pattern w.r.t the argument vector x. -*/ -virtual bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const vector< std::set >& r , - const vector< std::set >& u , - vector< std::set >& v ) -{ return false; } -virtual bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const vector& r , - const vector& u , - vector& v ) -{ return false; } -virtual bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const vectorBool& r , - const vectorBool& u , - vectorBool& v ) -{ return false; } -/* ------------------------------------------------------------------------------- -$begin atomic_base_clear$$ -$spell - sq - alloc -$$ - -$section Free Static Variables$$ -$mindex clear$$ - -$head Syntax$$ -$codei%atomic_base<%Base%>::clear()%$$ - -$head Purpose$$ -Each $code atomic_base$$ objects holds onto work space in order to -avoid repeated memory allocation calls and thereby increase speed -(until it is deleted). -If an the $code atomic_base$$ object is global or static because, -the it does not get deleted. -This is a problem when using -$code thread_alloc$$ $cref/free_all/ta_free_all/$$ -to check that all allocated memory has been freed. -Calling this $code clear$$ function will free all the -memory currently being held onto by the -$codei%atomic_base<%Base%>%$$ class. - -$head Future Use$$ -If there is future use of an $code atomic_base$$ object, -after a call to $code clear$$, -the work space will be reallocated and held onto. - -$head Restriction$$ -This routine cannot be called -while in $cref/parallel/ta_in_parallel/$$ execution mode. - -$end ------------------------------------------------------------------------------- -*/ -/*! -Free all thread_alloc static memory held by atomic_base (avoids reallocations). -(This does not include class_object() which is an std::vector.) -*/ -/// Free vector memory used by this class (work space) -static void clear(void) -{ CPPAD_ASSERT_KNOWN( - ! thread_alloc::in_parallel() , - "cannot use atomic_base clear during parallel execution" - ); - size_t i = class_object().size(); - while(i--) - { size_t thread = CPPAD_MAX_NUM_THREADS; - while(thread--) - { - atomic_base* op = class_object()[i]; - if( op != CPPAD_NULL ) - { op->afun_vx_[thread].clear(); - op->afun_vy_[thread].clear(); - op->afun_tx_[thread].clear(); - op->afun_ty_[thread].clear(); - } - } - } - return; -} -// ------------------------------------------------------------------------- -/*! -Set value of id (used by deprecated old_atomic class) - -This function is called just before calling any of the virtual funcitons -and has the corresponding id of the corresponding virtual call. -*/ -virtual void set_id(size_t id) -{ } -// --------------------------------------------------------------------------- -}; -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/azmul.hpp b/ct_core/include/ct/external/cppad/local/azmul.hpp deleted file mode 100644 index 7158aea35..000000000 --- a/ct_core/include/ct/external/cppad/local/azmul.hpp +++ /dev/null @@ -1,214 +0,0 @@ -// $Id$ -# ifndef CPPAD_AZMUL_HPP -# define CPPAD_AZMUL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin azmul$$ -$spell - azmul - const - namespace - Vec -$$ - -$section Absolute Zero Multiplication$$ - -$head Syntax$$ -$icode%z% = azmul(%x%, %y%)%$$ - -$head Purpose$$ -Evaluates multiplication with an absolute zero -for any of the possible types listed below. -The result is given by -$latex \[ -z = \left\{ \begin{array}{ll} - 0 & {\rm if} \; x = 0 \\ - x \cdot y & {\rm otherwise} -\end{array} \right. -\] $$ -Note if $icode x$$ is zero and $icode y$$ is infinity, -ieee multiplication would result in not a number whereas -$icode z$$ would be zero. - -$head Base$$ -If $icode Base$$ satisfies the -$cref/base type requirements/base_require/$$ -and arguments $icode x$$, $icode y$$ have prototypes -$codei% - const %Base%& %x% - const %Base%& %y% -%$$ -then the result $icode z$$ has prototype -$codei% - %Base% %z% -%$$ - -$head AD$$ -If the arguments $icode x$$, $icode y$$ have prototype -$codei% - const AD<%Base%>& %x% - const AD<%Base%>& %y% -%$$ -then the result $icode z$$ has prototype -$codei% - AD<%Base%> %z% -%$$ - -$head VecAD$$ -If the arguments $icode x$$, $icode y$$ have prototype -$codei% - const VecAD<%Base%>::reference& %x% - const VecAD<%Base%>::reference& %y% -%$$ -then the result $icode z$$ has prototype -$codei% - AD<%Base%> %z% -%$$ - -$head Example$$ -$children% - example/azmul.cpp -%$$ -The file -$cref azmul.cpp$$ -is an examples and tests of this function. -It returns true if it succeeds and false otherwise. - -$end -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -// ========================================================================== - -// case where x and y are AD ------------------------------------------- -template AD -azmul(const AD& x, const AD& y) -{ - // compute the Base part - AD result; - result.value_ = azmul(x.value_, y.value_); - - // check if there is a recording in progress - ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return result; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_x = x.tape_id_ == tape_id; - bool var_y = y.tape_id_ == tape_id; - - if( var_x ) - { if( var_y ) - { // result = azmul(variable, variable) - CPPAD_ASSERT_UNKNOWN( NumRes(ZmulvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(ZmulvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(x.taddr_, y.taddr_); - - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(ZmulvvOp); - - // make result a variable - result.tape_id_ = tape_id; - } - else if( IdenticalZero( y.value_ ) ) - { // result = variable * 0 - } - else if( IdenticalOne( y.value_ ) ) - { // result = variable * 1 - result.make_variable(x.tape_id_, x.taddr_); - } - else - { // result = zmul(variable, parameter) - CPPAD_ASSERT_UNKNOWN( NumRes(ZmulvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(ZmulvpOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(y.value_); - tape->Rec_.PutArg(x.taddr_, p); - - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(ZmulvpOp); - - // make result a variable - result.tape_id_ = tape_id; - } - } - else if( var_y ) - { if( IdenticalZero(x.value_) ) - { // result = 0 * variable - } - else if( IdenticalOne( x.value_ ) ) - { // result = 1 * variable - result.make_variable(y.tape_id_, y.taddr_); - } - else - { // result = zmul(parameter, variable) - CPPAD_ASSERT_UNKNOWN( NumRes(ZmulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(ZmulpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(x.value_); - tape->Rec_.PutArg(p, y.taddr_); - - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(ZmulpvOp); - - // make result a variable - result.tape_id_ = tape_id; - } - } - return result; -} -// ========================================================================= -// Fold operations into case above -// ------------------------------------------------------------------------- -// Operations with VecAD_reference and AD only - -template AD -azmul(const AD& x, const VecAD_reference& y) -{ return azmul(x, y.ADBase()); } - -template AD -azmul(const VecAD_reference& x, const VecAD_reference& y) -{ return azmul(x.ADBase(), y.ADBase()); } - -template AD -azmul(const VecAD_reference& x, const AD& y) -{ return azmul(x.ADBase(), y); } -// ------------------------------------------------------------------------- -// Operations with Base - -template AD -azmul(const Base& x, const AD& y) -{ return azmul(AD(x), y); } - -template AD -azmul(const Base& x, const VecAD_reference& y) -{ return azmul(AD(x), y.ADBase()); } - -template AD -azmul(const AD& x, const Base& y) -{ return azmul(x, AD(y)); } - -template AD -azmul(const VecAD_reference& x, const Base& y) -{ return azmul(x.ADBase(), AD(y)); } - -// ========================================================================== -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/base_complex.hpp b/ct_core/include/ct/external/cppad/local/base_complex.hpp deleted file mode 100644 index 4c2671eec..000000000 --- a/ct_core/include/ct/external/cppad/local/base_complex.hpp +++ /dev/null @@ -1,384 +0,0 @@ -// $Id: base_complex.hpp 3768 2015-12-28 18:58:35Z bradbell $ -# ifndef CPPAD_BASE_COMPLEX_HPP -# define CPPAD_BASE_COMPLEX_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include -# include - -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -/* -$begin base_complex.hpp$$ -$spell - azmul - expm1 - atanh - acosh - asinh - endif - eps - abs_geq - Rel - Lt Le Eq Ge Gt - imag - gcc - isnan - cppad.hpp - sqrt - exp - cos - std - const - CppAD - Op - inline - enum - undef - acos - asin - atan - erf - Cond - namespace - bool -$$ - - -$section Enable use of AD where Base is std::complex$$ - -$children%example/complex_poly.cpp -%$$ -$head Example$$ -The file $cref complex_poly.cpp$$ contains an example use of -$code std::complex$$ type for a CppAD $icode Base$$ type. -It returns true if it succeeds and false otherwise. - -$head Include Order$$ -This file is included before $code $$ -so it is necessary to define the error handler -in addition to including -$cref/base_require.hpp/base_require/Include Order/$$ -$codep */ -# include -# include -# include -# include - -/* $$ - -$head CondExpOp$$ -The type $code std::complex$$ does not supports the -$code <$$, $code <=$$, $code ==$$, $code >=$$, and $code >$$ operators; see -$cref/not ordered/base_cond_exp/CondExpTemplate/Not Ordered/$$. -Hence its $code CondExpOp$$ function is defined by -$codep */ -namespace CppAD { - inline std::complex CondExpOp( - enum CppAD::CompareOp cop , - const std::complex &left , - const std::complex &right , - const std::complex &trueCase , - const std::complex &falseCase ) - { CppAD::ErrorHandler::Call( - true , __LINE__ , __FILE__ , - "std::complex CondExpOp(...)", - "Error: cannot use CondExp with a complex type" - ); - return std::complex(0); - } -} -/* $$ - -$head CondExpRel$$ -The $cref/CPPAD_COND_EXP_REL/base_cond_exp/CondExpRel/$$ macro invocation -$codep */ -namespace CppAD { - CPPAD_COND_EXP_REL( std::complex ) -} -/* $$ -used $code CondExpOp$$ above to -define $codei%CondExp%Rel%$$ for $code std::complex$$ arguments -and $icode%Rel%$$ equal to -$code Lt$$, $code Le$$, $code Eq$$, $code Ge$$, and $code Gt$$. - -$head EqualOpSeq$$ -Complex numbers do not carry operation sequence information. -Thus they are equal in this sense if and only if there values are equal. -$codep */ -namespace CppAD { - inline bool EqualOpSeq( - const std::complex &x , - const std::complex &y ) - { return x == y; - } -} -/* $$ - -$head Identical$$ -Complex numbers do not carry operation sequence information. -Thus they are all parameters so the identical functions just check values. -$codep */ -namespace CppAD { - inline bool IdenticalPar(const std::complex &x) - { return true; } - inline bool IdenticalZero(const std::complex &x) - { return (x == std::complex(0., 0.) ); } - inline bool IdenticalOne(const std::complex &x) - { return (x == std::complex(1., 0.) ); } - inline bool IdenticalEqualPar( - const std::complex &x, const std::complex &y) - { return (x == y); } -} -/* $$ - -$head Ordered$$ -Complex types do not support comparison operators, -$codep */ -# undef CPPAD_USER_MACRO -# define CPPAD_USER_MACRO(Fun) \ -inline bool Fun(const std::complex& x) \ -{ CppAD::ErrorHandler::Call( \ - true , __LINE__ , __FILE__ , \ - #Fun"(x)", \ - "Error: cannot use " #Fun " with x complex " \ - ); \ - return false; \ -} -namespace CppAD { - CPPAD_USER_MACRO(LessThanZero) - CPPAD_USER_MACRO(LessThanOrZero) - CPPAD_USER_MACRO(GreaterThanOrZero) - CPPAD_USER_MACRO(GreaterThanZero) - inline bool abs_geq( - const std::complex& x , - const std::complex& y ) - { return std::abs(x) >= std::abs(y); } -} -/* $$ - -$head Integer$$ -The implementation of this function must agree -with the CppAD user specifications for complex arguments to the -$cref/Integer/Integer/x/Complex Types/$$ function: -$codep */ -namespace CppAD { - inline int Integer(const std::complex &x) - { return static_cast( x.real() ); } -} -/* $$ - -$head azmul$$ -$codep */ -namespace CppAD { - CPPAD_AZMUL( std::complex ) -} -/* $$ - -$head isnan$$ -The gcc 4.1.1 complier defines the function -$codei% - int std::complex::isnan( std::complex %z% ) -%$$ -(which is not specified in the C++ 1998 standard ISO/IEC 14882). -This causes an ambiguity between the function above and the CppAD -$cref/isnan/nan/$$ template function. -We avoid this ambiguity by defining a non-template version of -this function in the CppAD namespace. -$codep */ -namespace CppAD { - inline bool isnan(const std::complex& z) - { return (z != z); - } -} -/* $$ - -$head Valid Unary Math$$ -The following macro invocations define the standard unary -math functions that are valid with complex arguments and are -required to use $code AD< std::complex >$$. -$codep */ -namespace CppAD { - CPPAD_STANDARD_MATH_UNARY(std::complex, cos) - CPPAD_STANDARD_MATH_UNARY(std::complex, cosh) - CPPAD_STANDARD_MATH_UNARY(std::complex, exp) - CPPAD_STANDARD_MATH_UNARY(std::complex, log) - CPPAD_STANDARD_MATH_UNARY(std::complex, sin) - CPPAD_STANDARD_MATH_UNARY(std::complex, sinh) - CPPAD_STANDARD_MATH_UNARY(std::complex, sqrt) -} -/* $$ - -$head Invalid Unary Math$$ -The following macro definition and invocations define the standard unary -math functions that are invalid with complex arguments and are -required to use $code AD< std::complex >$$. -$codep */ -# undef CPPAD_USER_MACRO -# define CPPAD_USER_MACRO(Fun) \ -inline std::complex Fun(const std::complex& x) \ -{ CppAD::ErrorHandler::Call( \ - true , __LINE__ , __FILE__ , \ - #Fun"(x)", \ - "Error: cannot use " #Fun " with x complex " \ - ); \ - return std::complex(0); \ -} -namespace CppAD { - CPPAD_USER_MACRO(abs) - CPPAD_USER_MACRO(acos) - CPPAD_USER_MACRO(asin) - CPPAD_USER_MACRO(atan) - CPPAD_USER_MACRO(sign) -# if CPPAD_USE_CPLUSPLUS_2011 - CPPAD_USER_MACRO(erf) - CPPAD_USER_MACRO(asinh) - CPPAD_USER_MACRO(acosh) - CPPAD_USER_MACRO(atanh) - CPPAD_USER_MACRO(expm1) - CPPAD_USER_MACRO(log1p) -# endif -} -/* $$ - -$head pow $$ -The following defines a $code CppAD::pow$$ function that -is required to use $code AD< std::complex >$$: -$codep */ -namespace CppAD { - inline std::complex pow( - const std::complex &x , - const std::complex &y ) - { return std::pow(x, y); } -} -/*$$ - -$head numeric_limits$$ -The following defines the CppAD $cref numeric_limits$$ -for the type $code std::complex$$: -$codep */ -namespace CppAD { - CPPAD_NUMERIC_LIMITS(double, std::complex) -} -/*$$ - -$head to_string$$ -The following defines the function CppAD $cref to_string$$ -for the type $code std::complex$$: -$codep */ -namespace CppAD { - CPPAD_TO_STRING(std::complex) -} -/* $$ -$end -*/ -# undef CPPAD_USER_MACRO_ONE -# define CPPAD_USER_MACRO_ONE(Fun) \ -inline bool Fun(const std::complex& x) \ -{ CppAD::ErrorHandler::Call( \ - true , __LINE__ , __FILE__ , \ - #Fun"(x)", \ - "Error: cannot use " #Fun " with x complex " \ - ); \ - return false; \ -} -# undef CPPAD_USER_MACRO_TWO -# define CPPAD_USER_MACRO_TWO(Fun) \ -inline std::complex Fun(const std::complex& x) \ -{ CppAD::ErrorHandler::Call( \ - true , __LINE__ , __FILE__ , \ - #Fun"(x)", \ - "Error: cannot use " #Fun " with x complex " \ - ); \ - return std::complex(0); \ -} -namespace CppAD { - // CondExpOp ------------------------------------------------------ - inline std::complex CondExpOp( - enum CppAD::CompareOp cop , - const std::complex &left , - const std::complex &right , - const std::complex &trueCase , - const std::complex &falseCase ) - { CppAD::ErrorHandler::Call( - true , __LINE__ , __FILE__ , - "std::complex CondExpOp(...)", - "Error: cannot use CondExp with a complex type" - ); - return std::complex(0); - } - // CondExpRel -------------------------------------------------------- - CPPAD_COND_EXP_REL( std::complex ) - // EqualOpSeq ----------------------------------------------------- - inline bool EqualOpSeq( - const std::complex &x , - const std::complex &y ) - { return x == y; - } - // Identical ------------------------------------------------------ - inline bool IdenticalPar(const std::complex &x) - { return true; } - inline bool IdenticalZero(const std::complex &x) - { return (x == std::complex(0., 0.) ); } - inline bool IdenticalOne(const std::complex &x) - { return (x == std::complex(1., 0.) ); } - inline bool IdenticalEqualPar( - const std::complex &x, const std::complex &y) - { return (x == y); } - // Ordered -------------------------------------------------------- - CPPAD_USER_MACRO_ONE(LessThanZero) - CPPAD_USER_MACRO_ONE(LessThanOrZero) - CPPAD_USER_MACRO_ONE(GreaterThanOrZero) - CPPAD_USER_MACRO_ONE(GreaterThanZero) - inline bool abs_geq( - const std::complex& x , - const std::complex& y ) - { return std::abs(x) >= std::abs(y); } - // Integer ------------------------------------------------------ - inline int Integer(const std::complex &x) - { return static_cast( x.real() ); } - // isnan ------------------------------------------------------------- - inline bool isnan(const std::complex& z) - { return (z != z); - } - // Valid standard math functions -------------------------------- - CPPAD_STANDARD_MATH_UNARY(std::complex, cos) - CPPAD_STANDARD_MATH_UNARY(std::complex, cosh) - CPPAD_STANDARD_MATH_UNARY(std::complex, exp) - CPPAD_STANDARD_MATH_UNARY(std::complex, log) - CPPAD_STANDARD_MATH_UNARY(std::complex, sin) - CPPAD_STANDARD_MATH_UNARY(std::complex, sinh) - CPPAD_STANDARD_MATH_UNARY(std::complex, sqrt) - // Invalid standrd math functions ------------------------------- - CPPAD_USER_MACRO_TWO(abs) - CPPAD_USER_MACRO_TWO(acos) - CPPAD_USER_MACRO_TWO(asin) - CPPAD_USER_MACRO_TWO(atan) - CPPAD_USER_MACRO_TWO(sign) - // The pow function - inline std::complex pow( - const std::complex &x , - const std::complex &y ) - { return std::pow(x, y); } - // numeric_limits ------------------------------------------------- - CPPAD_NUMERIC_LIMITS(float, std::complex) - // to_string ------------------------------------------------- - CPPAD_TO_STRING(std::complex) -} - -// undefine macros only used by this file -# undef CPPAD_USER_MACRO -# undef CPPAD_USER_MACRO_ONE -# undef CPPAD_USER_MACRO_TWO - -# endif diff --git a/ct_core/include/ct/external/cppad/local/base_cond_exp.hpp b/ct_core/include/ct/external/cppad/local/base_cond_exp.hpp deleted file mode 100644 index bd970b60c..000000000 --- a/ct_core/include/ct/external/cppad/local/base_cond_exp.hpp +++ /dev/null @@ -1,281 +0,0 @@ -// $Id: base_cond_exp.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_BASE_COND_EXP_HPP -# define CPPAD_BASE_COND_EXP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin base_cond_exp$$ -$spell - alloc - Rel - hpp - enum - namespace - Op - Lt - Le - Eq - Ge - Gt - Ne - cond - exp - const - adolc - CppAD - inline -$$ - -$section Base Type Requirements for Conditional Expressions$$ -$mindex CondExp require CPPAD_COND_EXP_REL$$ - -$head Purpose$$ -These definitions are required by the user's code to support the -$codei%AD<%Base%>%$$ type for $cref CondExp$$ operations: - -$head CompareOp$$ -The following $code enum$$ type is used in the specifications below: -$codep -namespace CppAD { - // The conditional expression operator enum type - enum CompareOp - { CompareLt, // less than - CompareLe, // less than or equal - CompareEq, // equal - CompareGe, // greater than or equal - CompareGt, // greater than - CompareNe // not equal - }; -} -$$ - -$head CondExpTemplate$$ -The type $icode Base$$ must support the syntax -$codei% - %result% = CppAD::CondExpOp( - %cop%, %left%, %right%, %exp_if_true%, %exp_if_false% - ) -%$$ -which computes implements the corresponding $cref CondExp$$ -function when the result has prototype -$codei% - %Base% %result% -%$$ -The argument $icode cop$$ has prototype -$codei% - enum CppAD::CompareOp %cop% -%$$ -The other arguments have the prototype -$codei% - const %Base%& %left% - const %Base%& %right% - const %Base%& %exp_if_true% - const %Base%& %exp_if_false% -%$$ - -$subhead Ordered Type$$ -If $icode Base$$ is a relatively simple type -that supports -$code <$$, $code <=$$, $code ==$$, $code >=$$, and $code >$$ operators -its $code CondExpOp$$ function can be defined by -$codei% -namespace CppAD { - inline %Base% CondExpOp( - enum CppAD::CompareOp cop , - const %Base% &left , - const %Base% &right , - const %Base% &exp_if_true , - const %Base% &exp_if_false ) - { return CondExpTemplate( - cop, left, right, trueCase, falseCase); - } -} -%$$ -For example, see -$cref/double CondExpOp/base_alloc.hpp/CondExpOp/$$. -For an example of and implementation of $code CondExpOp$$ with -a more involved $icode Base$$ type see -$cref/adolc CondExpOp/base_adolc.hpp/CondExpOp/$$. - - -$subhead Not Ordered$$ -If the type $icode Base$$ does not support ordering, -the $code CondExpOp$$ function does not make sense. -In this case one might (but need not) define $code CondExpOp$$ as follows: -$codei% -namespace CppAD { - inline %Base% CondExpOp( - enum CompareOp cop , - const %Base% &left , - const %Base% &right , - const %Base% &exp_if_true , - const %Base% &exp_if_false ) - { // attempt to use CondExp with a %Base% argument - assert(0); - return %Base%(0); - } -} -%$$ -For example, see -$cref/complex CondExpOp/base_complex.hpp/CondExpOp/$$. - -$head CondExpRel$$ -The macro invocation -$codei% - CPPAD_COND_EXP_REL(%Base%) -%$$ -uses $code CondExpOp$$ above to define the following functions -$codei% - CondExpLt(%left%, %right%, %exp_if_true%, %exp_if_false%) - CondExpLe(%left%, %right%, %exp_if_true%, %exp_if_false%) - CondExpEq(%left%, %right%, %exp_if_true%, %exp_if_false%) - CondExpGe(%left%, %right%, %exp_if_true%, %exp_if_false%) - CondExpGt(%left%, %right%, %exp_if_true%, %exp_if_false%) -%$$ -where the arguments have type $icode Base$$. -This should be done inside of the CppAD namespace. -For example, see -$cref/base_alloc/base_alloc.hpp/CondExpRel/$$. - -$end -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -/*! -\file base_cond_exp.hpp -CondExp operations that aid in meeting Base type requirements. -*/ - -/*! -\def CPPAD_COND_EXP_BASE_REL(Type, Rel, Op) -This macro defines the operation -\verbatim - CondExpRel(left, right, exp_if_true, exp_if_false) -\endverbatim -The argument \c Type is the \c Base type for this base require operation. -The argument \c Rel is one of \c Lt, \c Le, \c Eq, \c Ge, \c Gt. -The argument \c Op is the corresponding \c CompareOp value. -*/ -# define CPPAD_COND_EXP_BASE_REL(Type, Rel, Op) \ - inline Type CondExp##Rel( \ - const Type& left , \ - const Type& right , \ - const Type& exp_if_true , \ - const Type& exp_if_false ) \ - { return CondExpOp(Op, left, right, exp_if_true, exp_if_false); \ - } - -/*! -\def CPPAD_COND_EXP_REL(Type) -The macro defines the operations -\verbatim - CondExpLt(left, right, exp_if_true, exp_if_false) - CondExpLe(left, right, exp_if_true, exp_if_false) - CondExpEq(left, right, exp_if_true, exp_if_false) - CondExpGe(left, right, exp_if_true, exp_if_false) - CondExpGt(left, right, exp_if_true, exp_if_false) -\endverbatim -The argument \c Type is the \c Base type for this base require operation. -*/ -# define CPPAD_COND_EXP_REL(Type) \ - CPPAD_COND_EXP_BASE_REL(Type, Lt, CompareLt) \ - CPPAD_COND_EXP_BASE_REL(Type, Le, CompareLe) \ - CPPAD_COND_EXP_BASE_REL(Type, Eq, CompareEq) \ - CPPAD_COND_EXP_BASE_REL(Type, Ge, CompareGe) \ - CPPAD_COND_EXP_BASE_REL(Type, Gt, CompareGt) - -/*! -Template function to implement Conditional Expressions for simple types -that have comparision operators. - -\tparam CompareType -is the type of the left and right operands to the comparision operator. - -\tparam ResultType -is the type of the result, which is the same as \c CompareType except -during forward and reverse mode sparese calculations. - -\param cop -specifices which comparision to use; i.e., -$code <$$, -$code <=$$, -$code ==$$, -$code >=$$, -$code >$$, or -$code !=$$. - -\param left -is the left operand to the comparision operator. - -\param right -is the right operand to the comparision operator. - -\param exp_if_true -is the return value is the comparision results in true. - -\param exp_if_false -is the return value is the comparision results in false. - -\return -see \c exp_if_true and \c exp_if_false above. -*/ -template -ResultType CondExpTemplate( - enum CompareOp cop , - const CompareType& left , - const CompareType& right , - const ResultType& exp_if_true , - const ResultType& exp_if_false ) -{ ResultType returnValue; - switch( cop ) - { - case CompareLt: - if( left < right ) - returnValue = exp_if_true; - else returnValue = exp_if_false; - break; - - case CompareLe: - if( left <= right ) - returnValue = exp_if_true; - else returnValue = exp_if_false; - break; - - case CompareEq: - if( left == right ) - returnValue = exp_if_true; - else returnValue = exp_if_false; - break; - - case CompareGe: - if( left >= right ) - returnValue = exp_if_true; - else returnValue = exp_if_false; - break; - - case CompareGt: - if( left > right ) - returnValue = exp_if_true; - else returnValue = exp_if_false; - break; - - default: - CPPAD_ASSERT_UNKNOWN(0); - returnValue = exp_if_true; - } - return returnValue; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/base_double.hpp b/ct_core/include/ct/external/cppad/local/base_double.hpp deleted file mode 100644 index 2b4d3df27..000000000 --- a/ct_core/include/ct/external/cppad/local/base_double.hpp +++ /dev/null @@ -1,222 +0,0 @@ -// $Id: base_double.hpp 3769 2015-12-29 16:13:16Z bradbell $ -# ifndef CPPAD_BASE_DOUBLE_HPP -# define CPPAD_BASE_DOUBLE_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include - -/* -$begin base_double.hpp$$ -$spell - cppad - hpp - azmul - expm1 - atanh - acosh - asinh - erf - endif - abs_geq - acos - asin - atan - cos - sqrt - tanh - std - fabs - bool - Lt Le Eq Ge Gt - Rel - CppAD - CondExpOp - namespace - inline - enum - const - exp - const -$$ - - -$section Enable use of AD where Base is double$$ - -$head CondExpOp$$ -The type $code double$$ is a relatively simple type that supports -$code <$$, $code <=$$, $code ==$$, $code >=$$, and $code >$$ operators; see -$cref/ordered type/base_cond_exp/CondExpTemplate/Ordered Type/$$. -Hence its $code CondExpOp$$ function is defined by -$codep */ -namespace CppAD { - inline double CondExpOp( - enum CompareOp cop , - const double& left , - const double& right , - const double& exp_if_true , - const double& exp_if_false ) - { return CondExpTemplate(cop, left, right, exp_if_true, exp_if_false); - } -} -/* $$ - -$head CondExpRel$$ -The $cref/CPPAD_COND_EXP_REL/base_cond_exp/CondExpRel/$$ macro invocation -$codep */ -namespace CppAD { - CPPAD_COND_EXP_REL(double) -} -/* $$ -uses $code CondExpOp$$ above to -define $codei%CondExp%Rel%$$ for $code double$$ arguments -and $icode%Rel%$$ equal to -$code Lt$$, $code Le$$, $code Eq$$, $code Ge$$, and $code Gt$$. - -$head EqualOpSeq$$ -The type $code double$$ is simple (in this respect) and so we define -$codep */ -namespace CppAD { - inline bool EqualOpSeq(const double& x, const double& y) - { return x == y; } -} -/* $$ - -$head Identical$$ -The type $code double$$ is simple (in this respect) and so we define -$codep */ -namespace CppAD { - inline bool IdenticalPar(const double& x) - { return true; } - inline bool IdenticalZero(const double& x) - { return (x == 0.); } - inline bool IdenticalOne(const double& x) - { return (x == 1.); } - inline bool IdenticalEqualPar(const double& x, const double& y) - { return (x == y); } -} -/* $$ - -$head Integer$$ -$codep */ -namespace CppAD { - inline int Integer(const double& x) - { return static_cast(x); } -} -/* $$ - -$head azmul$$ -$codep */ -namespace CppAD { - CPPAD_AZMUL( double ) -} -/* $$ - -$head Ordered$$ -The $code double$$ type supports ordered comparisons -$codep */ -namespace CppAD { - inline bool GreaterThanZero(const double& x) - { return x > 0.; } - inline bool GreaterThanOrZero(const double& x) - { return x >= 0.; } - inline bool LessThanZero(const double& x) - { return x < 0.; } - inline bool LessThanOrZero(const double& x) - { return x <= 0.; } - inline bool abs_geq(const double& x, const double& y) - { return std::fabs(x) >= std::fabs(y); } -} -/* $$ - -$head Unary Standard Math$$ -The following macro invocations define the unary standard math functions -required to use $code AD$$: -$codep */ -namespace CppAD { - CPPAD_STANDARD_MATH_UNARY(double, acos) - CPPAD_STANDARD_MATH_UNARY(double, asin) - CPPAD_STANDARD_MATH_UNARY(double, atan) - CPPAD_STANDARD_MATH_UNARY(double, cos) - CPPAD_STANDARD_MATH_UNARY(double, cosh) - CPPAD_STANDARD_MATH_UNARY(double, exp) - CPPAD_STANDARD_MATH_UNARY(double, fabs) - CPPAD_STANDARD_MATH_UNARY(double, log) - CPPAD_STANDARD_MATH_UNARY(double, log10) - CPPAD_STANDARD_MATH_UNARY(double, sin) - CPPAD_STANDARD_MATH_UNARY(double, sinh) - CPPAD_STANDARD_MATH_UNARY(double, sqrt) - CPPAD_STANDARD_MATH_UNARY(double, tan) - CPPAD_STANDARD_MATH_UNARY(double, tanh) -# if CPPAD_USE_CPLUSPLUS_2011 - CPPAD_STANDARD_MATH_UNARY(double, erf) - CPPAD_STANDARD_MATH_UNARY(double, asinh) - CPPAD_STANDARD_MATH_UNARY(double, acosh) - CPPAD_STANDARD_MATH_UNARY(double, atanh) - CPPAD_STANDARD_MATH_UNARY(double, expm1) - CPPAD_STANDARD_MATH_UNARY(double, log1p) -# endif -} -/* $$ -The absolute value function is special because its $code std$$ name is -$code fabs$$ -$codep */ -namespace CppAD { - inline double abs(const double& x) - { return std::fabs(x); } -} -/* $$ - -$head sign$$ -The following defines the $code CppAD::sign$$ function that -is required to use $code AD$$: -$codep */ -namespace CppAD { - inline double sign(const double& x) - { if( x > 0. ) - return 1.; - if( x == 0. ) - return 0.; - return -1.; - } -} -/* $$ - -$head pow $$ -The following defines a $code CppAD::pow$$ function that -is required to use $code AD$$: -$codep */ -namespace CppAD { - inline double pow(const double& x, const double& y) - { return std::pow(x, y); } -} -/*$$ - -$head numeric_limits$$ -The following defines the CppAD $cref numeric_limits$$ -for the type $code double$$: -$codep */ -namespace CppAD { - CPPAD_NUMERIC_LIMITS(double, double) -} -/*$$ - -$head to_string$$ -There is no need to define $code to_string$$ for $code double$$ -because it is defined by including $code cppad/utility/to_string.hpp$$; -see $cref to_string$$. -See $cref/base_complex.hpp/base_complex.hpp/to_string/$$ for an example where -it is necessary to define $code to_string$$ for a $icode Base$$ type. - -$end -*/ - -# endif diff --git a/ct_core/include/ct/external/cppad/local/base_float.hpp b/ct_core/include/ct/external/cppad/local/base_float.hpp deleted file mode 100644 index 41150e5ef..000000000 --- a/ct_core/include/ct/external/cppad/local/base_float.hpp +++ /dev/null @@ -1,224 +0,0 @@ -// $Id: base_float.hpp 3769 2015-12-29 16:13:16Z bradbell $ -# ifndef CPPAD_BASE_FLOAT_HPP -# define CPPAD_BASE_FLOAT_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include - -/* -$begin base_float.hpp$$ -$spell - cppad - hpp - azmul - expm1 - atanh - acosh - asinh - erf - endif - abs_geq - acos - asin - atan - cos - sqrt - tanh - std - fabs - bool - Lt Le Eq Ge Gt - Rel - CppAD - CondExpOp - namespace - inline - enum - const - exp - const -$$ - - -$section Enable use of AD where Base is float$$ - -$head CondExpOp$$ -The type $code float$$ is a relatively simple type that supports -$code <$$, $code <=$$, $code ==$$, $code >=$$, and $code >$$ operators; see -$cref/ordered type/base_cond_exp/CondExpTemplate/Ordered Type/$$. -Hence its $code CondExpOp$$ function is defined by -$codep */ -namespace CppAD { - inline float CondExpOp( - enum CompareOp cop , - const float& left , - const float& right , - const float& exp_if_true , - const float& exp_if_false ) - { return CondExpTemplate(cop, left, right, exp_if_true, exp_if_false); - } -} -/* $$ - -$head CondExpRel$$ -The $cref/CPPAD_COND_EXP_REL/base_cond_exp/CondExpRel/$$ macro invocation -$codep */ -namespace CppAD { - CPPAD_COND_EXP_REL(float) -} -/* $$ -uses $code CondExpOp$$ above to -define $codei%CondExp%Rel%$$ for $code float$$ arguments -and $icode%Rel%$$ equal to -$code Lt$$, $code Le$$, $code Eq$$, $code Ge$$, and $code Gt$$. - -$head EqualOpSeq$$ -The type $code float$$ is simple (in this respect) and so we define -$codep */ -namespace CppAD { - inline bool EqualOpSeq(const float& x, const float& y) - { return x == y; } -} -/* $$ - -$head Identical$$ -The type $code float$$ is simple (in this respect) and so we define -$codep */ -namespace CppAD { - inline bool IdenticalPar(const float& x) - { return true; } - inline bool IdenticalZero(const float& x) - { return (x == 0.f); } - inline bool IdenticalOne(const float& x) - { return (x == 1.f); } - inline bool IdenticalEqualPar(const float& x, const float& y) - { return (x == y); } -} -/* $$ - -$head Integer$$ -$codep */ -namespace CppAD { - inline int Integer(const float& x) - { return static_cast(x); } -} -/* $$ - -$head azmul$$ -$codep */ -namespace CppAD { - CPPAD_AZMUL( float ) -} -/* $$ - -$head Ordered$$ -The $code float$$ type supports ordered comparisons -$codep */ -namespace CppAD { - inline bool GreaterThanZero(const float& x) - { return x > 0.f; } - inline bool GreaterThanOrZero(const float& x) - { return x >= 0.f; } - inline bool LessThanZero(const float& x) - { return x < 0.f; } - inline bool LessThanOrZero(const float& x) - { return x <= 0.f; } - inline bool abs_geq(const float& x, const float& y) - { return std::fabs(x) >= std::fabs(y); } -} -/* $$ - -$head Unary Standard Math$$ -The following macro invocations define the unary standard math functions -required to use $code AD$$: -(in the CppAD namespace) -$codep */ -namespace CppAD { - CPPAD_STANDARD_MATH_UNARY(float, acos) - CPPAD_STANDARD_MATH_UNARY(float, asin) - CPPAD_STANDARD_MATH_UNARY(float, atan) - CPPAD_STANDARD_MATH_UNARY(float, cos) - CPPAD_STANDARD_MATH_UNARY(float, cosh) - CPPAD_STANDARD_MATH_UNARY(float, exp) - CPPAD_STANDARD_MATH_UNARY(float, fabs) - CPPAD_STANDARD_MATH_UNARY(float, log) - CPPAD_STANDARD_MATH_UNARY(float, log10) - CPPAD_STANDARD_MATH_UNARY(float, sin) - CPPAD_STANDARD_MATH_UNARY(float, sinh) - CPPAD_STANDARD_MATH_UNARY(float, sqrt) - CPPAD_STANDARD_MATH_UNARY(float, tan) - CPPAD_STANDARD_MATH_UNARY(float, tanh) -# if CPPAD_USE_CPLUSPLUS_2011 - CPPAD_STANDARD_MATH_UNARY(float, erf) - CPPAD_STANDARD_MATH_UNARY(float, asinh) - CPPAD_STANDARD_MATH_UNARY(float, acosh) - CPPAD_STANDARD_MATH_UNARY(float, atanh) - CPPAD_STANDARD_MATH_UNARY(float, expm1) - CPPAD_STANDARD_MATH_UNARY(float, log1p) -# endif -} -/* $$ -The absolute value function is special because its $code std$$ name is -$code fabs$$ -$codep */ -namespace CppAD { - inline float abs(const float& x) - { return std::fabs(x); } -} -/* $$ - -$head sign$$ -The following defines the $code CppAD::sign$$ function that -is required to use $code AD$$: -$codep */ -namespace CppAD { - inline float sign(const float& x) - { if( x > 0.f ) - return 1.f; - if( x == 0.f ) - return 0.f; - return -1.f; - } -} -/* $$ - -$head pow $$ -The following defines a $code CppAD::pow$$ function that -is required to use $code AD$$: -$codep */ -namespace CppAD { - inline float pow(const float& x, const float& y) - { return std::pow(x, y); } -} -/*$$ - -$head numeric_limits$$ -The following defines the CppAD $cref numeric_limits$$ -for the type $code float$$: -$codep */ -namespace CppAD { - CPPAD_NUMERIC_LIMITS(float, float) -} -/*$$ - -$head to_string$$ -There is no need to define $code to_string$$ for $code float$$ -because it is defined by including $code cppad/utility/to_string.hpp$$; -see $cref to_string$$. -See $cref/base_complex.hpp/base_complex.hpp/to_string/$$ for an example where -it is necessary to define $code to_string$$ for a $icode Base$$ type. - -$end -*/ - - -# endif diff --git a/ct_core/include/ct/external/cppad/local/base_limits.hpp b/ct_core/include/ct/external/cppad/local/base_limits.hpp deleted file mode 100644 index 334dd48de..000000000 --- a/ct_core/include/ct/external/cppad/local/base_limits.hpp +++ /dev/null @@ -1,67 +0,0 @@ -// $Id$ -# ifndef CPPAD_BASE_LIMITS_HPP -# define CPPAD_BASE_LIMITS_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin base_limits$$ -$spell - std - namespace - CppAD -$$ - -$section Base Type Requirements for Numeric Limits$$ - -$head CppAD::numeric_limits$$ -A specialization for -$cref/CppAD::numeric_limits/numeric_limits/$$ -must be defined in order to use the type $codei%AD<%Base%>%$$. -CppAD does not use a specialization of -$codei%std::numeric_limits<%Base%>%$$. -Since C++11, using a specialization of -$codei%std::numeric_limits<%Base%>%$$ -would require that $icode Base$$ be a literal type. - -$head CPPAD_NUMERIC_LIMITS$$ -In most cases, this macro can be used to define the specialization where -the numeric limits for the type $icode Base$$ -are the same as the standard numeric limits for the type $icode Other$$. -For most $icode Base$$ types, -there is a choice of $icode Other$$, -for which the following preprocessor macro invocation suffices: -$codei% - namespace CppAD { - CPPAD_NUMERIC_LIMITS(%Other%, %Base%) - } -%$$ -where the macro is defined by -$codep */ -# define CPPAD_NUMERIC_LIMITS(Other, Base) \ -template <> class numeric_limits\ -{\ - public:\ - static Base min(void) \ - { return static_cast( std::numeric_limits::min() ); }\ - static Base max(void) \ - { return static_cast( std::numeric_limits::max() ); }\ - static Base epsilon(void) \ - { return static_cast( std::numeric_limits::epsilon() ); }\ - static Base quiet_NaN(void) \ - { return static_cast( std::numeric_limits::quiet_NaN() ); }\ -}; -/* $$ -$end -*/ - -# endif diff --git a/ct_core/include/ct/external/cppad/local/base_std_math.hpp b/ct_core/include/ct/external/cppad/local/base_std_math.hpp deleted file mode 100644 index e293b14f7..000000000 --- a/ct_core/include/ct/external/cppad/local/base_std_math.hpp +++ /dev/null @@ -1,186 +0,0 @@ -// $Id: base_std_math.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_BASE_STD_MATH_HPP -# define CPPAD_BASE_STD_MATH_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin base_std_math$$ -$spell - expm1 - atanh - acosh - asinh - inline - fabs - isnan - alloc - std - acos - asin - atan - cos - exp - sqrt - const - CppAD - namespace - erf -$$ - -$section Base Type Requirements for Standard Math Functions$$ - -$head Purpose$$ -These definitions are required for the user's code to use the type -$codei%AD<%Base%>%$$: - -$head Unary Standard Math$$ -The type $icode Base$$ must support the following functions -unary standard math functions (in the CppAD namespace): -$table -$bold Syntax$$ $cnext $bold Result$$ -$rnext -$icode%y% = abs(%x%)%$$ $cnext absolute value $rnext -$icode%y% = acos(%x%)%$$ $cnext inverse cosine $rnext -$icode%y% = asin(%x%)%$$ $cnext inverse sine $rnext -$icode%y% = atan(%x%)%$$ $cnext inverse tangent $rnext -$icode%y% = cos(%x%)%$$ $cnext cosine $rnext -$icode%y% = cosh(%x%)%$$ $cnext hyperbolic cosine $rnext -$icode%y% = exp(%x%)%$$ $cnext exponential $rnext -$icode%y% = fabs(%x%)%$$ $cnext absolute value $rnext -$icode%y% = log(%x%)%$$ $cnext natural logarithm $rnext -$icode%y% = sin(%x%)%$$ $cnext sine $rnext -$icode%y% = sinh(%x%)%$$ $cnext hyperbolic sine $rnext -$icode%y% = sqrt(%x%)%$$ $cnext square root $rnext -$icode%y% = tan(%x%)%$$ $cnext tangent -$tend -where the arguments and return value have the prototypes -$codei% - const %Base%& %x% - %Base% %y% -%$$ -For example, -$cref/base_alloc/base_alloc.hpp/Unary Standard Math/$$, - - -$head CPPAD_STANDARD_MATH_UNARY$$ -The macro invocation, within the CppAD namespace, -$codei% - CPPAD_STANDARD_MATH_UNARY(%Base%, %Fun%) -%$$ -defines the syntax -$codei% - %y% = CppAD::%Fun%(%x%) -%$$ -This macro uses the functions $codei%std::%Fun%$$ which -must be defined and have the same prototype as $codei%CppAD::%Fun%$$. -For example, -$cref/float/base_float.hpp/Unary Standard Math/$$. - -$head erf, asinh, acosh, atanh, expm1, log1p$$ -If this preprocessor symbol -$code CPPAD_USE_CPLUSPLUS_2011$$ is true ($code 1$$), -when compiling for c++11, the type -$code double$$ is supported for the functions listed below. -In this case, the type $icode Base$$ must also support these functions: -$table -$bold Syntax$$ $cnext $bold Result$$ -$rnext -$icode%y% = erf(%x%)%$$ $cnext error function $rnext -$icode%y% = asinh(%x%)%$$ $cnext inverse hyperbolic sin $rnext -$icode%y% = acosh(%x%)%$$ $cnext inverse hyperbolic cosine $rnext -$icode%y% = atanh(%x%)%$$ $cnext inverse hyperbolic tangent $rnext -$icode%y% = expm1(%x%)%$$ $cnext exponential of x minus one $rnext -$icode%y% = log1p(%x%)%$$ $cnext logarithm of one plus x -$tend -where the arguments and return value have the prototypes -$codei% - const %Base%& %x% - %Base% %y% -%$$ - -$head sign$$ -The type $icode Base$$ must support the syntax -$codei% - %y% = CppAD::sign(%x%) -%$$ -which computes -$latex \[ -y = \left\{ \begin{array}{ll} - +1 & {\rm if} \; x > 0 \\ - 0 & {\rm if} \; x = 0 \\ - -1 & {\rm if} \; x < 0 -\end{array} \right. -\] $$ -where $icode x$$ and $icode y$$ have the same prototype as above. -For example, see -$cref/base_alloc/base_alloc.hpp/sign/$$. -Note that, if ordered comparisons are not defined for the type $icode Base$$, -the $code code sign$$ function should generate an assert if it is used; see -$cref/complex invalid unary math/base_complex.hpp/Invalid Unary Math/$$. - -$head pow$$ -The type $icode Base$$ must support the syntax -$codei% - %z% = CppAD::pow(%x%, %y%) -%$$ -which computes $latex z = x^y$$. -The arguments $icode x$$ and $icode y$$ have prototypes -$codei% - const %Base%& %x% - const %Base%& %y% -%$$ -and the return value $icode z$$ has prototype -$codei% - %Base% %z% -%$$ -For example, see -$cref/base_alloc/base_alloc.hpp/pow/$$. - - -$head isnan$$ -If $icode Base$$ defines the $code isnan$$ function, -you may also have to provide a definition in the CppAD namespace -(to avoid a function ambiguity). -For example, see -$cref/base_complex/base_complex.hpp/isnan/$$. - - -$end -------------------------------------------------------------------------------- -*/ - -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -/*! -\file base_std_math.hpp -Defintions that aid meeting Base type requirements for standard math functions. -*/ - -/*! -\def CPPAD_STANDARD_MATH_UNARY(Type, Fun) -This macro defines the function -\verbatim - y = CppAD:Fun(x) -\endverbatim -where the argument \c x and return value \c y have type \c Type -using the corresponding function std::Fun. -*/ -# define CPPAD_STANDARD_MATH_UNARY(Type, Fun) \ - inline Type Fun(const Type& x) \ - { return std::Fun(x); } - -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/base_to_string.hpp b/ct_core/include/ct/external/cppad/local/base_to_string.hpp deleted file mode 100644 index a46b79cbc..000000000 --- a/ct_core/include/ct/external/cppad/local/base_to_string.hpp +++ /dev/null @@ -1,68 +0,0 @@ -// $Id$ -# ifndef CPPAD_BASE_TO_STRING_HPP -# define CPPAD_BASE_TO_STRING_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin base_to_string$$ -$spell - std - namespace - CppAD - struct - const - stringstream - setprecision - str -$$ - -$section Extending to_string To Another Floating Point Type$$ - -$head Base Requirement$$ -If the function $cref to_string$$ is used by an -$cref/AD type above Base/glossary/AD Type Above Base/$$, -A specialization for the template structure -$code CppAD::to_string_struct$$ must be defined. - -$head CPPAD_TO_STRING$$ -For most $icode Base$$ types, -the following can be used to define the specialization: -$codei% - namespace CppAD { - CPPAD_TO_STRING(%Base%) - } -%$$ -Note that the $code CPPAD_TO_STRING$$ macro assumes that the -$cref base_limits$$ and $cref base_std_math$$ have already been defined -for this type. -This macro is defined as follows: -$codep */ -# define CPPAD_TO_STRING(Base) \ -template <> struct to_string_struct\ -{ std::string operator()(const Base& value) \ - { std::stringstream os;\ - Base epsilon = CppAD::numeric_limits::epsilon();\ - Base log10 = CppAD::log( epsilon ) / CppAD::log(Base(10.));\ - size_t n_digits = 1 - Integer( log10 );\ - os << std::setprecision(n_digits);\ - os << value;\ - return os.str();\ - }\ -}; -/* $$ -$end ------------------------------------------------------------------------------- -*/ -// make sure to_string has been included -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/local/bender_quad.hpp b/ct_core/include/ct/external/cppad/local/bender_quad.hpp deleted file mode 100644 index 1099540df..000000000 --- a/ct_core/include/ct/external/cppad/local/bender_quad.hpp +++ /dev/null @@ -1,405 +0,0 @@ -// $Id: bender_quad.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_BENDER_QUAD_HPP -# define CPPAD_BENDER_QUAD_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin BenderQuad$$ -$spell - cppad.hpp - BAvector - gx - gxx - CppAD - Fy - dy - Jacobian - ADvector - const - dg - ddg -$$ - - -$section Computing Jacobian and Hessian of Bender's Reduced Objective$$ -$mindex BenderQuad$$ - -$head Syntax$$ -$codei% -# include -BenderQuad(%x%, %y%, %fun%, %g%, %gx%, %gxx%)%$$ - -$head See Also$$ -$cref opt_val_hes$$ - -$head Problem$$ -The type $cref/ADvector/BenderQuad/ADvector/$$ cannot be determined -form the arguments above -(currently the type $icode ADvector$$ must be -$codei%CPPAD_TESTVECTOR(%Base%)%$$.) -This will be corrected in the future by requiring $icode Fun$$ -to define $icode%Fun%::vector_type%$$ which will specify the -type $icode ADvector$$. - -$head Purpose$$ -We are given the optimization problem -$latex \[ -\begin{array}{rcl} -{\rm minimize} & F(x, y) & {\rm w.r.t.} \; (x, y) \in \B{R}^n \times \B{R}^m -\end{array} -\] $$ -that is convex with respect to $latex y$$. -In addition, we are given a set of equations $latex H(x, y)$$ -such that -$latex \[ - H[ x , Y(x) ] = 0 \;\; \Rightarrow \;\; F_y [ x , Y(x) ] = 0 -\] $$ -(In fact, it is often the case that $latex H(x, y) = F_y (x, y)$$.) -Furthermore, it is easy to calculate a Newton step for these equations; i.e., -$latex \[ - dy = - [ \partial_y H(x, y)]^{-1} H(x, y) -\] $$ -The purpose of this routine is to compute the -value, Jacobian, and Hessian of the reduced objective function -$latex \[ - G(x) = F[ x , Y(x) ] -\] $$ -Note that if only the value and Jacobian are needed, they can be -computed more quickly using the relations -$latex \[ - G^{(1)} (x) = \partial_x F [x, Y(x) ] -\] $$ - -$head x$$ -The $code BenderQuad$$ argument $icode x$$ has prototype -$codei% - const %BAvector% &%x% -%$$ -(see $cref/BAvector/BenderQuad/BAvector/$$ below) -and its size must be equal to $icode n$$. -It specifies the point at which we evaluating -the reduced objective function and its derivatives. - - -$head y$$ -The $code BenderQuad$$ argument $icode y$$ has prototype -$codei% - const %BAvector% &%y% -%$$ -and its size must be equal to $icode m$$. -It must be equal to $latex Y(x)$$; i.e., -it must solve the problem in $latex y$$ for this given value of $latex x$$ -$latex \[ -\begin{array}{rcl} - {\rm minimize} & F(x, y) & {\rm w.r.t.} \; y \in \B{R}^m -\end{array} -\] $$ - -$head fun$$ -The $code BenderQuad$$ object $icode fun$$ -must support the member functions listed below. -The $codei%AD<%Base%>%$$ arguments will be variables for -a tape created by a call to $cref Independent$$ from $code BenderQuad$$ -(hence they can not be combined with variables corresponding to a -different tape). - -$subhead fun.f$$ -The $code BenderQuad$$ argument $icode fun$$ supports the syntax -$codei% - %f% = %fun%.f(%x%, %y%) -%$$ -The $icode%fun%.f%$$ argument $icode x$$ has prototype -$codei% - const %ADvector% &%x% -%$$ -(see $cref/ADvector/BenderQuad/ADvector/$$ below) -and its size must be equal to $icode n$$. -The $icode%fun%.f%$$ argument $icode y$$ has prototype -$codei% - const %ADvector% &%y% -%$$ -and its size must be equal to $icode m$$. -The $icode%fun%.f%$$ result $icode f$$ has prototype -$codei% - %ADvector% %f% -%$$ -and its size must be equal to one. -The value of $icode f$$ is -$latex \[ - f = F(x, y) -\] $$. - -$subhead fun.h$$ -The $code BenderQuad$$ argument $icode fun$$ supports the syntax -$codei% - %h% = %fun%.h(%x%, %y%) -%$$ -The $icode%fun%.h%$$ argument $icode x$$ has prototype -$codei% - const %ADvector% &%x% -%$$ -and its size must be equal to $icode n$$. -The $icode%fun%.h%$$ argument $icode y$$ has prototype -$codei% - const %BAvector% &%y% -%$$ -and its size must be equal to $icode m$$. -The $icode%fun%.h%$$ result $icode h$$ has prototype -$codei% - %ADvector% %h% -%$$ -and its size must be equal to $icode m$$. -The value of $icode h$$ is -$latex \[ - h = H(x, y) -\] $$. - -$subhead fun.dy$$ -The $code BenderQuad$$ argument $icode fun$$ supports the syntax -$codei% - %dy% = %fun%.dy(%x%, %y%, %h%) - -%x% -%$$ -The $icode%fun%.dy%$$ argument $icode x$$ has prototype -$codei% - const %BAvector% &%x% -%$$ -and its size must be equal to $icode n$$. -Its value will be exactly equal to the $code BenderQuad$$ argument -$icode x$$ and values depending on it can be stored as private objects -in $icode f$$ and need not be recalculated. -$codei% - -%y% -%$$ -The $icode%fun%.dy%$$ argument $icode y$$ has prototype -$codei% - const %BAvector% &%y% -%$$ -and its size must be equal to $icode m$$. -Its value will be exactly equal to the $code BenderQuad$$ argument -$icode y$$ and values depending on it can be stored as private objects -in $icode f$$ and need not be recalculated. -$codei% - -%h% -%$$ -The $icode%fun%.dy%$$ argument $icode h$$ has prototype -$codei% - const %ADvector% &%h% -%$$ -and its size must be equal to $icode m$$. -$codei% - -%dy% -%$$ -The $icode%fun%.dy%$$ result $icode dy$$ has prototype -$codei% - %ADvector% %dy% -%$$ -and its size must be equal to $icode m$$. -The return value $icode dy$$ is given by -$latex \[ - dy = - [ \partial_y H (x , y) ]^{-1} h -\] $$ -Note that if $icode h$$ is equal to $latex H(x, y)$$, -$latex dy$$ is the Newton step for finding a zero -of $latex H(x, y)$$ with respect to $latex y$$; -i.e., -$latex y + dy$$ is an approximate solution for the equation -$latex H (x, y + dy) = 0$$. - -$head g$$ -The argument $icode g$$ has prototype -$codei% - %BAvector% &%g% -%$$ -and has size one. -The input value of its element does not matter. -On output, -it contains the value of $latex G (x)$$; i.e., -$latex \[ - g[0] = G (x) -\] $$ - -$head gx$$ -The argument $icode gx$$ has prototype -$codei% - %BAvector% &%gx% -%$$ -and has size $latex n $$. -The input values of its elements do not matter. -On output, -it contains the Jacobian of $latex G (x)$$; i.e., -for $latex j = 0 , \ldots , n-1$$, -$latex \[ - gx[ j ] = G^{(1)} (x)_j -\] $$ - -$head gxx$$ -The argument $icode gx$$ has prototype -$codei% - %BAvector% &%gxx% -%$$ -and has size $latex n \times n$$. -The input values of its elements do not matter. -On output, -it contains the Hessian of $latex G (x)$$; i.e., -for $latex i = 0 , \ldots , n-1$$, and -$latex j = 0 , \ldots , n-1$$, -$latex \[ - gxx[ i * n + j ] = G^{(2)} (x)_{i,j} -\] $$ - -$head BAvector$$ -The type $icode BAvector$$ must be a -$cref SimpleVector$$ class. -We use $icode Base$$ to refer to the type of the elements of -$icode BAvector$$; i.e., -$codei% - %BAvector%::value_type -%$$ - -$head ADvector$$ -The type $icode ADvector$$ must be a -$cref SimpleVector$$ class with elements of type -$codei%AD<%Base%>%$$; i.e., -$codei% - %ADvector%::value_type -%$$ -must be the same type as -$codei% - AD< %BAvector%::value_type > -%$$. - - -$head Example$$ -$children% - example/bender_quad.cpp -%$$ -The file -$cref bender_quad.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - - -$end ------------------------------------------------------------------------------ -*/ - -namespace CppAD { // BEGIN CppAD namespace - -template -void BenderQuad( - const BAvector &x , - const BAvector &y , - Fun fun , - BAvector &g , - BAvector &gx , - BAvector &gxx ) -{ // determine the base type - typedef typename BAvector::value_type Base; - - // check that BAvector is a SimpleVector class - CheckSimpleVector(); - - // declare the ADvector type - typedef CPPAD_TESTVECTOR(AD) ADvector; - - // size of the x and y spaces - size_t n = size_t(x.size()); - size_t m = size_t(y.size()); - - // check the size of gx and gxx - CPPAD_ASSERT_KNOWN( - g.size() == 1, - "BenderQuad: size of the vector g is not equal to 1" - ); - CPPAD_ASSERT_KNOWN( - size_t(gx.size()) == n, - "BenderQuad: size of the vector gx is not equal to n" - ); - CPPAD_ASSERT_KNOWN( - size_t(gxx.size()) == n * n, - "BenderQuad: size of the vector gxx is not equal to n * n" - ); - - // some temporary indices - size_t i, j; - - // variable versions x - ADvector vx(n); - for(j = 0; j < n; j++) - vx[j] = x[j]; - - // declare the independent variables - Independent(vx); - - // evaluate h = H(x, y) - ADvector h(m); - h = fun.h(vx, y); - - // evaluate dy (x) = Newton step as a function of x through h only - ADvector dy(m); - dy = fun.dy(x, y, h); - - // variable version of y - ADvector vy(m); - for(j = 0; j < m; j++) - vy[j] = y[j] + dy[j]; - - // evaluate G~ (x) = F [ x , y + dy(x) ] - ADvector gtilde(1); - gtilde = fun.f(vx, vy); - - // AD function object that corresponds to G~ (x) - // We will make heavy use of this tape, so optimize it - ADFun Gtilde; - Gtilde.Dependent(vx, gtilde); - Gtilde.optimize(); - - // value of G(x) - g = Gtilde.Forward(0, x); - - // initial forward direction vector as zero - BAvector dx(n); - for(j = 0; j < n; j++) - dx[j] = Base(0); - - // weight, first and second order derivative values - BAvector dg(1), w(1), ddw(2 * n); - w[0] = 1.; - - - // Jacobian and Hessian of G(x) is equal Jacobian and Hessian of Gtilde - for(j = 0; j < n; j++) - { // compute partials in x[j] direction - dx[j] = Base(1); - dg = Gtilde.Forward(1, dx); - gx[j] = dg[0]; - - // restore the dx vector to zero - dx[j] = Base(0); - - // compute second partials w.r.t x[j] and x[l] for l = 1, n - ddw = Gtilde.Reverse(2, w); - for(i = 0; i < n; i++) - gxx[ i * n + j ] = ddw[ i * 2 + 1 ]; - } - - return; -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/bool_fun.hpp b/ct_core/include/ct/external/cppad/local/bool_fun.hpp deleted file mode 100644 index 1252f25ef..000000000 --- a/ct_core/include/ct/external/cppad/local/bool_fun.hpp +++ /dev/null @@ -1,244 +0,0 @@ -// $Id: bool_fun.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_BOOL_FUN_HPP -# define CPPAD_BOOL_FUN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin BoolFun$$ -$spell - namespace - bool - CppAD - const -$$ - - -$section AD Boolean Functions$$ -$mindex bool CPPAD_BOOL_UNARY CPPAD_BOOL_BINARY$$ - -$head Syntax$$ -$codei%CPPAD_BOOL_UNARY(%Base%, %unary_name%) -%$$ -$icode%b% = %unary_name%(%u%) -%$$ -$icode%b% = %unary_name%(%x%) -%$$ -$codei%CPPAD_BOOL_BINARY(%Base%, %binary_name%) -%$$ -$icode%b% = %binary_name%(%u%, %v%) -%$$ -$icode%b% = %binary_name%(%x%, %y%)%$$ - - -$head Purpose$$ -Create a $code bool$$ valued function that has $codei%AD<%Base%>%$$ arguments. - -$head unary_name$$ -This is the name of the $code bool$$ valued function with one argument -(as it is used in the source code). -The user must provide a version of $icode unary_name$$ where -the argument has type $icode Base$$. -CppAD uses this to create a version of $icode unary_name$$ where the -argument has type $codei%AD<%Base%>%$$. - -$head u$$ -The argument $icode u$$ has prototype -$codei% - const %Base% &%u% -%$$ -It is the value at which the user provided version of $icode unary_name$$ -is to be evaluated. -It is also used for the first argument to the -user provided version of $icode binary_name$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const AD<%Base%> &%x% -%$$ -It is the value at which the CppAD provided version of $icode unary_name$$ -is to be evaluated. -It is also used for the first argument to the -CppAD provided version of $icode binary_name$$. - -$head b$$ -The result $icode b$$ has prototype -$codei% - bool %b% -%$$ - -$head Create Unary$$ -The preprocessor macro invocation -$codei% - CPPAD_BOOL_UNARY(%Base%, %unary_name%) -%$$ -defines the version of $icode unary_name$$ with a $codei%AD<%Base%>%$$ -argument. -This can with in a namespace -(not the $code CppAD$$ namespace) -but must be outside of any routine. - -$head binary_name$$ -This is the name of the $code bool$$ valued function with two arguments -(as it is used in the source code). -The user must provide a version of $icode binary_name$$ where -the arguments have type $icode Base$$. -CppAD uses this to create a version of $icode binary_name$$ where the -arguments have type $codei%AD<%Base%>%$$. - -$head v$$ -The argument $icode v$$ has prototype -$codei% - const %Base% &%v% -%$$ -It is the second argument to -the user provided version of $icode binary_name$$. - -$head y$$ -The argument $icode x$$ has prototype -$codei% - const AD<%Base%> &%y% -%$$ -It is the second argument to -the CppAD provided version of $icode binary_name$$. - -$head Create Binary$$ -The preprocessor macro invocation -$codei% - CPPAD_BOOL_BINARY(%Base%, %binary_name%) -%$$ -defines the version of $icode binary_name$$ with $codei%AD<%Base%>%$$ -arguments. -This can with in a namespace -(not the $code CppAD$$ namespace) -but must be outside of any routine. - - -$head Operation Sequence$$ -The result of this operation is not an -$cref/AD of Base/glossary/AD of Base/$$ object. -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Example$$ -$children% - example/bool_fun.cpp -%$$ -The file -$cref bool_fun.cpp$$ -contains an example and test of these operations. -It returns true if it succeeds and false otherwise. - -$head Deprecated 2007-07-31$$ -The preprocessor symbols $code CppADCreateUnaryBool$$ -and $code CppADCreateBinaryBool$$ are defined to be the same as -$code CPPAD_BOOL_UNARY$$ and $code CPPAD_BOOL_BINARY$$ respectively -(but their use is deprecated). - -$end -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file bool_fun.hpp -Routines and macros that implement functions from AD to bool. -*/ - -/*! -Macro that defines a unary function bool F(AD x) -using bool F(Base x). - -\param Base -base for the AD type of arguments to this unary bool valued function. - -\param unary_name -name of this unary function; i.e., \c F. -*/ -# define CPPAD_BOOL_UNARY(Base, unary_name) \ - inline bool unary_name (const CppAD::AD &x) \ - { \ - return CppAD::AD::UnaryBool(unary_name, x); \ - } - -/*! -Deprecated name for CPPAD_BOOL_UNARY -*/ -# define CppADCreateUnaryBool CPPAD_BOOL_UNARY - -/*! -Link a function name, and AD value pair to function call with base argument -and bool retrun value. - -\param FunName -is the name of the function that we are linking. - -\param x -is the argument where we are evaluating the function. -*/ -template -inline bool AD::UnaryBool( - bool FunName(const Base &x), - const AD &x -) -{ - return FunName(x.value_); -} - -/*! -Macro that defines a binary function bool F(AD x, AD y) -using bool F(Base x, Base y). - -\param Base -base for the AD type of arguments to this binary bool valued function. - -\param binary_name -name of this binary function; i.e., \c F. -*/ - -# define CPPAD_BOOL_BINARY(Base, binary_name) \ - inline bool binary_name ( \ - const CppAD::AD &x, const CppAD::AD &y) \ - { \ - return CppAD::AD::BinaryBool(binary_name, x, y); \ - } -/*! -Deprecated name for CPPAD_BOOL_BINARY -*/ -# define CppADCreateBinaryBool CPPAD_BOOL_BINARY - - -/*! -Link a function name, and two AD values to function call with base arguments -and bool retrun value. - -\param FunName -is the name of the function that we are linking. - -\param x -is the first argument where we are evaluating the function at. - -\param y -is the second argument where we are evaluating the function at. -*/ -template -inline bool AD::BinaryBool( - bool FunName(const Base &x, const Base &y), - const AD &x, const AD &y -) -{ - return FunName(x.value_, y.value_); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/bool_valued.hpp b/ct_core/include/ct/external/cppad/local/bool_valued.hpp deleted file mode 100644 index ac2fdaba1..000000000 --- a/ct_core/include/ct/external/cppad/local/bool_valued.hpp +++ /dev/null @@ -1,50 +0,0 @@ -// $Id: bool_valued.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_BOOL_VALUED_HPP -# define CPPAD_BOOL_VALUED_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin BoolValued$$ -$spell - Bool -$$ - - -$section Bool Valued Operations and Functions with AD Arguments$$ - -$children% - cppad/local/compare.hpp% - cppad/local/near_equal_ext.hpp% - cppad/local/bool_fun.hpp% - cppad/local/par_var.hpp% - cppad/local/equal_op_seq.hpp -%$$ -$table -$rref Compare$$ -$rref NearEqualExt$$ -$rref BoolFun$$ -$rref ParVar$$ -$rref EqualOpSeq$$ -$tend - - -$end -*/ - -# include -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/local/capacity_order.hpp b/ct_core/include/ct/external/cppad/local/capacity_order.hpp deleted file mode 100644 index c3c6f56b1..000000000 --- a/ct_core/include/ct/external/cppad/local/capacity_order.hpp +++ /dev/null @@ -1,260 +0,0 @@ -// $Id: capacity_order.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_CAPACITY_ORDER_HPP -# define CPPAD_CAPACITY_ORDER_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin capacity_order$$ -$spell - var - taylor_ - xq - yq -$$ - - -$section Controlling Taylor Coefficients Memory Allocation$$ -$mindex Forward capacity_order control$$ - -$head Syntax$$ -$icode%f%.capacity_order(%c%)%$$ - -$subhead See Also$$ -$cref seq_property$$ - -$head Purpose$$ -The Taylor coefficients calculated by $cref Forward$$ mode calculations -are retained in an $cref ADFun$$ object for subsequent use during -$cref Reverse$$ mode and higher order Forward mode calculations. -For example, a call to $cref/Forward/forward_order/$$ with the syntax -$codei% - %yq% = %f%.Forward(%q%, %xq%) -%$$ -where $icode%q% > 0%$$ and $code%xq%.size() == %f%.Domain()%$$, -uses the lower order Taylor coefficients and -computes the $th q$$ order Taylor coefficients for all -the variables in the operation sequence corresponding to $icode f$$. -The $code capacity_order$$ operation allows you to control that -amount of memory that is retained by an AD function object -(to hold $code Forward$$ results for subsequent calculations). - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ - -$head c$$ -The argument $icode c$$ has prototype -$codei% - size_t %c% -%$$ -It specifies the number of Taylor coefficient orders that are allocated -in the AD operation sequence corresponding to $icode f$$. - -$subhead Pre-Allocating Memory$$ -If you plan to make calls to $code Forward$$ with the maximum value of -$icode q$$ equal to $icode Q$$, -it should be faster to pre-allocate memory for these calls using -$codei% - %f%.capacity_order(%c%) -%$$ -with $icode c$$ equal to $latex Q + 1$$. -If you do no do this, $code Forward$$ will automatically allocate memory -and will copy the results to a larger buffer, when necessary. -$pre - -$$ -Note that each call to $cref Dependent$$ frees the old memory -connected to the function object and sets the corresponding -taylor capacity to zero. - -$subhead Freeing Memory$$ -If you no longer need the Taylor coefficients of order $icode q$$ -and higher (that are stored in $icode f$$), -you can reduce the memory allocated to $icode f$$ using -$codei% - %f%.capacity_order(%c%) -%$$ -with $icode c$$ equal to $icode q$$. -Note that, if $cref ta_hold_memory$$ is true, this memory is not actually -returned to the system, but rather held for future use by the same thread. - -$head Original State$$ -If $icode f$$ is $cref/constructed/FunConstruct/$$ with the syntax -$codei% - ADFun<%Base%> %f%(%x%, %y%) -%$$, -there is an implicit call to $cref forward_zero$$ with $icode xq$$ equal to -the value of the -$cref/independent variables/glossary/Tape/Independent Variable/$$ -when the AD operation sequence was recorded. -This corresponds to $icode%c% == 1%$$. - -$children% - example/capacity_order.cpp -%$$ -$head Example$$ -The file -$cref capacity_order.cpp$$ -contains an example and test of these operations. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file capacity_order.hpp -Control of number of orders allocated. -\} -*/ - -/*! -Control of number of orders and directions allocated. - -\tparam Base -The type used during the forward mode computations; i.e., the corresponding -recording of operations used the type AD. - -\param c -is the number of orders to allocate memory for. -If c == 0 then \c r must also be zero. -In this case num_order_taylor_, cap_order_taylor_, and num_direction_taylor_ -are all set to zero. -In addition, taylor_.free() is called. - -\param r -is the number of directions to allocate memory for. -If c == 1 then \c r must also be one. -In all cases, it must hold that - - r == num_direction_taylor_ || num_order_taylor <= 1 - -Upon return, num_direction_taylor_ is equal to r. - -\par num_order_taylor_ -The output value of num_order_taylor_ is the mininumum of its input -value and c. This minimum is the number of orders that are copied to the -new taylor coefficient buffer. - -\par num_direction_taylor_ -The output value of num_direction_taylor_ is equal to \c r. -*/ - -template -void ADFun::capacity_order(size_t c, size_t r) -{ // temporary indices - size_t i, k, ell; - - if( (c == cap_order_taylor_) & (r == num_direction_taylor_) ) - return; - - if( c == 0 ) - { CPPAD_ASSERT_UNKNOWN( r == 0 ); - taylor_.free(); - num_order_taylor_ = 0; - cap_order_taylor_ = 0; - num_direction_taylor_ = r; - return; - } - CPPAD_ASSERT_UNKNOWN(r==num_direction_taylor_ || num_order_taylor_<=1); - - // Allocate new taylor with requested number of orders and directions - size_t new_len = ( (c-1)*r + 1 ) * num_var_tape_; - pod_vector new_taylor; - new_taylor.extend(new_len); - - // number of orders to copy - size_t p = std::min(num_order_taylor_, c); - if( p > 0 ) - { - // old order capacity - size_t C = cap_order_taylor_; - - // old number of directions - size_t R = num_direction_taylor_; - - // copy the old data into the new matrix - CPPAD_ASSERT_UNKNOWN( p == 1 || r == R ); - for(i = 0; i < num_var_tape_; i++) - { // copy zero order - size_t old_index = ((C-1) * R + 1) * i + 0; - size_t new_index = ((c-1) * r + 1) * i + 0; - new_taylor[ new_index ] = taylor_[ old_index ]; - // copy higher orders - for(k = 1; k < p; k++) - { for(ell = 0; ell < R; ell++) - { old_index = ((C-1) * R + 1) * i + (k-1) * R + ell + 1; - new_index = ((c-1) * r + 1) * i + (k-1) * r + ell + 1; - new_taylor[ new_index ] = taylor_[ old_index ]; - } - } - } - } - - // replace taylor_ by new_taylor - taylor_.swap(new_taylor); - cap_order_taylor_ = c; - num_order_taylor_ = p; - num_direction_taylor_ = r; - - // note that the destructor for new_taylor will free the old taylor memory - return; -} - -/*! -User API control of number of orders allocated. - -\tparam Base -The type used during the forward mode computations; i.e., the corresponding -recording of operations used the type AD. - -\param c -is the number of orders to allocate memory for. -If c == 0, -num_order_taylor_, cap_order_taylor_, and num_direction_taylor_ -are all set to zero. -In addition, taylor_.free() is called. - -\par num_order_taylor_ -The output value of num_order_taylor_ is the mininumum of its input -value and c. This minimum is the number of orders that are copied to the -new taylor coefficient buffer. - -\par num_direction_taylor_ -If \c is zero (one), \c num_direction_taylor_ is set to zero (one). -Otherwise, if \c num_direction_taylor_ is zero, it is set to one. -Othwerwise, \c num_direction_taylor_ is not modified. -*/ - -template -void ADFun::capacity_order(size_t c) -{ size_t r; - if( (c == 0) | (c == 1) ) - { r = c; - capacity_order(c, r); - return; - } - r = num_direction_taylor_; - if( r == 0 ) - r = 1; - capacity_order(c, r); - return; -} - -} // END CppAD namespace - - -# endif diff --git a/ct_core/include/ct/external/cppad/local/check_for_nan.hpp b/ct_core/include/ct/external/cppad/local/check_for_nan.hpp deleted file mode 100644 index 190f36b84..000000000 --- a/ct_core/include/ct/external/cppad/local/check_for_nan.hpp +++ /dev/null @@ -1,199 +0,0 @@ -// $Id$ -# ifndef CPPAD_CHECK_FOR_NAN_HPP -# define CPPAD_CHECK_FOR_NAN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin check_for_nan$$ -$spell - std - vec - Cpp - const - bool - newline -$$ -$section Check an ADFun Object For Nan Results$$ - -$head Syntax$$ -$icode%f%.check_for_nan(%b%) -%$$ -$icode%b% = %f%.check_for_nan() -%$$ -$codei%get_check_for_nan(%vec%, %file%) -%$$ - -$head Debugging$$ -If $code NDEBUG$$ is not defined, and -the result of a $cref/forward/forward_order/$$ or $cref/reverse/reverse_any/$$ -calculation contains a $cref nan$$, -CppAD can halt with an error message. - -$head f$$ -For the syntax where $icode b$$ is an argument, -$icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -(see $codei%ADFun<%Base%>%$$ $cref/constructor/FunConstruct/$$). -For the syntax where $icode b$$ is the result, -$icode f$$ has prototype -$codei% - const ADFun<%Base%> %f% -%$$ - -$head b$$ -This argument or result has prototype -$codei% - bool %b% -%$$ -Future calls to $icode%f%.Forward%$$ will (will not) check for $code nan$$. -depending on if $icode b$$ is true (false). - -$head Default$$ -The value for this setting after construction of $icode f$$) is true. -The value of this setting is not affected by calling -$cref Dependent$$ for this function object. - -$head Error Message$$ -If this error is detected during zero order forward mode, -the values of the independent variables that resulted in the $code nan$$ -are written to a temporary binary file. -This is so that you can run the original source code with those values -to see what is causing the $code nan$$. - -$subhead vector_size$$ -The error message with contain the text -$codei%vector_size = %vector_size%$$ followed the newline character -$code '\n'$$. -The value of $icode vector_size$$ is the number of elements -in the independent vector. - -$subhead file_name$$ -The error message with contain the text -$codei%file_name = %file_name%$$ followed the newline character -$code '\n'$$. -The value of $icode file_name$$ is the name of the temporary file -that contains the dependent variable values. - -$subhead index$$ -The error message will contain the text -$codei%index = %index%$$ followed by the newline character $code '\n'$$. -The value of $icode index$$ is the lowest dependent variable index -that has the value $code nan$$. - -$head get_check_for_nan$$ -This routine can be used to get the independent variable -values that result in a $code nan$$. - -$subhead vec$$ -This argument has prototype -$codei% - CppAD::vector<%Base%>& %vec% -%$$ -It size must be equal to the corresponding value of -$cref/vector_size/check_for_nan/Error Message/vector_size/$$ -in the corresponding error message. -The input value of its elements does not matter. -Upon return, it will contain the values for the independent variables, -in the corresponding call to $cref Independent$$, -that resulted in the $code nan$$. -(Note that the call to $code Independent$$ uses an vector with elements -of type $codei%AD<%Base%>%$$ and $icode vec$$ has elements of type -$icode Base$$.) - -$subhead file$$ -This argument has prototype -$codei% - const std::string& %file% -%$$ -It must be the value of -$cref/file_name/check_for_nan/Error Message/file_name/$$ -in the corresponding error message. - -$head Example$$ -$children% - example/check_for_nan.cpp -%$$ -The file -$cref check_for_nan.cpp$$ -contains an example and test of these operations. -It returns true if it succeeds and false otherwise. - -$end -*/ - -# include -# include -# include - -# if CPPAD_HAS_MKSTEMP -# include -# include -# else -# if CPPAD_HAS_TMPNAM_S -# include -# else -# include -# endif -# endif - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -template -void put_check_for_nan(const CppAD::vector& vec, std::string& file_name) -{ - size_t char_size = sizeof(Base) * vec.size(); - const char* char_ptr = reinterpret_cast( vec.data() ); -# if CPPAD_HAS_MKSTEMP - char pattern[] = "/tmp/fileXXXXXX"; - int fd = mkstemp(pattern); - file_name = pattern; - write(fd, char_ptr, char_size); - close(fd); -# else -# if CPPAD_HAS_TMPNAM_S - std::vector name(L_tmpnam_s); - if( tmpnam_s( name.data(), L_tmpnam_s ) != 0 ) - { CPPAD_ASSERT_KNOWN( - false, - "Cannot create a temporary file name" - ); - } - file_name = name.data(); -# else - file_name = tmpnam( CPPAD_NULL ); -# endif - std::fstream file_out(file_name.c_str(), std::ios::out|std::ios::binary ); - file_out.write(char_ptr, char_size); - file_out.close(); -# endif - return; -} - -template -void get_check_for_nan(CppAD::vector& vec, const std::string& file_name) -{ // - size_t n = vec.size(); - size_t char_size = sizeof(Base) * n; - char* char_ptr = reinterpret_cast( vec.data() ); - // - std::fstream file_in(file_name.c_str(), std::ios::in|std::ios::binary ); - file_in.read(char_ptr, char_size); - // - return; -} - -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/checkpoint.hpp b/ct_core/include/ct/external/cppad/local/checkpoint.hpp deleted file mode 100644 index 7ca81e69a..000000000 --- a/ct_core/include/ct/external/cppad/local/checkpoint.hpp +++ /dev/null @@ -1,983 +0,0 @@ -// $Id: checkpoint.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_CHECKPOINT_HPP -# define CPPAD_CHECKPOINT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file checkpoint.hpp -defining checkpoint functions. -*/ - -/* -$begin checkpoint$$ -$spell - sv - var - cppad.hpp - CppAD - checkpoint - checkpointing - algo - atom_fun - const - enum - bool -$$ - -$section Checkpointing Functions$$ - -$head Syntax$$ -$codei%checkpoint<%Base%> %atom_fun%(%name%, %algo%, %ax%, %ay%, %sparsity%) -%sv% = %atom_fun%.size_var() -%atom_fun%.option(%option_value%) -%algo%(%ax%, %ay%) -%atom_fun%(%ax%, %ay%) -checkpoint<%Base%>::clear()%$$ - -$head Purpose$$ - -$subhead Reduce Memory$$ -You can reduce the size of the tape and memory required for AD by -checkpointing functions of the form $latex y = f(x)$$ where -$latex f : B^n \rightarrow B^m$$. -The $cref/operation sequence/glossary/Operation/Sequence/$$ -representing $latex f(x)$$ cannot depend on the value of $latex x$$. - -$subhead Faster Recording$$ -It may also reduce the time to make a recording the same function -for different values of the independent variable. -Note that the operation sequence for a recording that uses $latex f(x)$$ -may depend on its independent variables. - -$head Method$$ -The $code checkpoint$$ class is derived from $code atomic_base$$ -and makes this easy. -It implements all the $code atomic_base$$ -$cref/virtual functions/atomic_base/Virtual Functions/$$ -and hence its source code $code cppad/local/checkpoint.hpp$$ -provides an example implementation of $cref atomic_base$$. -The difference is that $code checkpoint.hpp$$ uses AD -instead of user provided derivatives. - -$head constructor$$ -The syntax for the checkpoint constructor is -$codei% - checkpoint<%Base%> %atom_fun%(%name%, %algo%, %ax%, %ay%) -%$$ -$list number$$ -This constructor cannot be called in $cref/parallel/ta_in_parallel/$$ mode. -$lnext -You cannot currently be recording -$codei%AD<%Base%>%$$ operations when the constructor is called. -$lnext -This object $icode atom_fun$$ must not be destructed for as long -as any $codei%ADFun<%Base%>%$$ object uses its atomic operation. -$lnext -This class is implemented as a derived class of -$cref/atomic_base/atomic_ctor/atomic_base/$$ and hence -some of its error message will refer to $code atomic_base$$. -$lend - -$head Base$$ -The type $icode Base$$ specifies the base type for AD operations. - -$head ADVector$$ -The type $icode ADVector$$ must be a -$cref/simple vector class/SimpleVector/$$ with elements of type -$codei%AD<%Base%>%$$. - -$head name$$ -This $icode checkpoint$$ constructor argument has prototype -$codei% - const char* %name% -%$$ -It is the name used for error reporting. -The suggested value for $icode name$$ is $icode atom_fun$$; i.e., -the same name as used for the object being constructed. - -$head ax$$ -This argument has prototype -$codei% - const %ADVector%& %ax% -%$$ -and size must be equal to $icode n$$. -It specifies vector $latex x \in B^n$$ -at which an $codei%AD<%Base%>%$$ version of -$latex y = f(x)$$ is to be evaluated. - -$head ay$$ -This argument has prototype -$codei% - %ADVector%& %ay% -%$$ -Its input size must be equal to $icode m$$ and does not change. -The input values of its elements do not matter. -Upon return, it is an $codei%AD<%Base%>%$$ version of -$latex y = f(x)$$. - -$head sparsity$$ -This argument has prototype -$codei% - atomic_base<%Base%>::option_enum %sparsity% -%$$ -It specifies $cref/sparsity/atomic_ctor/atomic_base/sparsity/$$ -in the $code atomic_base$$ constructor and must be either -$codei%atomic_base<%Base%>::pack_sparsity_enum%$$, -$codei%atomic_base<%Base%>::bool_sparsity_enum%$$, or -$codei%atomic_base<%Base%>::set_sparsity_enum%$$. -This argument is optional and its default value is unspecified. - - -$head size_var$$ -This $code size_var$$ member function return value has prototype -$codei% - size_t %sv% -%$$ -It is the $cref/size_var/seq_property/size_var/$$ for the -$codei%ADFun<%Base%>%$$ object is used to store the operation sequence -corresponding to $icode algo$$. - -$head option$$ -The $code option$$ syntax can be used to set the type of sparsity -pattern used by $icode atom_fun$$. -This is an $codei%atomic_base<%Base%>%$$ function and its documentation -can be found at $cref atomic_option$$. - -$head algo$$ -The type of $icode algo$$ is arbitrary, except for the fact that -the syntax -$codei% - %algo%(%ax%, %ay%) -%$$ -must evaluate the function $latex y = f(x)$$ using -$codei%AD<%Base%>%$$ operations. -In addition, we assume that the -$cref/operation sequence/glossary/Operation/Sequence/$$ -does not depend on the value of $icode ax$$. - -$head atom_fun$$ -Given $icode ax$$ it computes the corresponding value of $icode ay$$ -using the operation sequence corresponding to $icode algo$$. -If $codei%AD<%Base%>%$$ operations are being recorded, -it enters the computation as single operation in the recording -see $cref/start recording/Independent/Start Recording/$$. -(Currently each use of $icode atom_fun$$ actually corresponds to -$icode%m%+%n%+2%$$ operations and creates $icode m$$ new variables, -but this is not part of the CppAD specifications and my change.) - -$head clear$$ -The $code atomic_base$$ class holds onto static work space in order to -increase speed by avoiding system memory allocation calls. -This call makes to work space $cref/available/ta_available/$$ to -for other uses by the same thread. -This should be called when you are done using the -user atomic functions for a specific value of $icode Base$$. - -$subhead Restriction$$ -The $code clear$$ routine cannot be called -while in $cref/parallel/ta_in_parallel/$$ execution mode. - -$children% - example/atomic/checkpoint.cpp -%$$ -$head Example$$ -The file $cref checkpoint.cpp$$ contains an example and test -of these operations. -It returns true if it succeeds and false if it fails. - -$end -*/ -template -class checkpoint : public atomic_base { -// --------------------------------------------------------------------------- -private: - /// same as option_enum in base class - typedef typename atomic_base::option_enum option_enum; - // - /// AD function corresponding to this checkpoint object - ADFun f_; - // - /// sparsity for entire Jacobian f(x)^{(1)} does not change so can cache it - CPPAD_INTERNAL_SPARSE_SET jac_sparse_set_; - vectorBool jac_sparse_bool_; - // - /// sparsity for sum_i f_i(x)^{(2)} does not change so can cache it - CPPAD_INTERNAL_SPARSE_SET hes_sparse_set_; - vectorBool hes_sparse_bool_; - // ------------------------------------------------------------------------ - option_enum sparsity(void) - { return static_cast< atomic_base* >(this)->sparsity(); } - // ------------------------------------------------------------------------ - /// set jac_sparse_set_ - void set_jac_sparse_set(void) - { CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.n_set() == 0 ); - bool transpose = false; - bool dependency = true; - size_t n = f_.Domain(); - size_t m = f_.Range(); - // Use the choice for forward / reverse that results in smaller - // size for the sparsity pattern of all variables in the tape. - if( n <= m ) - { CPPAD_INTERNAL_SPARSE_SET identity; - identity.resize(n, n); - for(size_t j = 0; j < n; j++) - identity.add_element(j, j); - f_.ForSparseJacCheckpoint( - n, identity, transpose, dependency, jac_sparse_set_ - ); - f_.size_forward_set(0); - } - else - { CPPAD_INTERNAL_SPARSE_SET identity; - identity.resize(m, m); - for(size_t i = 0; i < m; i++) - identity.add_element(i, i); - f_.RevSparseJacCheckpoint( - m, identity, transpose, dependency, jac_sparse_set_ - ); - } - CPPAD_ASSERT_UNKNOWN( f_.size_forward_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( f_.size_forward_bool() == 0 ); - } - /// set jac_sparse_bool_ - void set_jac_sparse_bool(void) - { CPPAD_ASSERT_UNKNOWN( jac_sparse_bool_.size() == 0 ); - bool transpose = false; - bool dependency = true; - size_t n = f_.Domain(); - size_t m = f_.Range(); - // Use the choice for forward / reverse that results in smaller - // size for the sparsity pattern of all variables in the tape. - if( n <= m ) - { vectorBool identity(n * n); - for(size_t j = 0; j < n; j++) - { for(size_t i = 0; i < n; i++) - identity[ i * n + j ] = (i == j); - } - jac_sparse_bool_ = f_.ForSparseJac( - n, identity, transpose, dependency - ); - f_.size_forward_bool(0); - } - else - { vectorBool identity(m * m); - for(size_t j = 0; j < m; j++) - { for(size_t i = 0; i < m; i++) - identity[ i * m + j ] = (i == j); - } - jac_sparse_bool_ = f_.RevSparseJac( - m, identity, transpose, dependency - ); - } - CPPAD_ASSERT_UNKNOWN( f_.size_forward_bool() == 0 ); - CPPAD_ASSERT_UNKNOWN( f_.size_forward_set() == 0 ); - } - // ------------------------------------------------------------------------ - /// set hes_sparse_set_ - void set_hes_sparse_set(void) - { CPPAD_ASSERT_UNKNOWN( hes_sparse_set_.n_set() == 0 ); - size_t n = f_.Domain(); - size_t m = f_.Range(); - // - // set version of sparsity for vector of all ones - vector all_one(m); - for(size_t i = 0; i < m; i++) - all_one[i] = true; - - // set version of sparsity for n by n idendity matrix - CPPAD_INTERNAL_SPARSE_SET identity; - identity.resize(n, n); - for(size_t j = 0; j < n; j++) - identity.add_element(j, j); - - // compute sparsity pattern for H(x) = sum_i f_i(x)^{(2)} - bool transpose = false; - bool dependency = false; - f_.ForSparseJacCheckpoint( - n, identity, transpose, dependency, jac_sparse_set_ - ); - f_.RevSparseHesCheckpoint( - n, all_one, transpose, hes_sparse_set_ - ); - CPPAD_ASSERT_UNKNOWN( hes_sparse_set_.n_set() == n ); - CPPAD_ASSERT_UNKNOWN( hes_sparse_set_.end() == n ); - // - // drop the forward sparsity results from f_ - f_.size_forward_set(0); - } - /// set hes_sparse_bool_ - void set_hes_sparse_bool(void) - { CPPAD_ASSERT_UNKNOWN( hes_sparse_bool_.size() == 0 ); - size_t n = f_.Domain(); - size_t m = f_.Range(); - // - // set version of sparsity for vector of all ones - vectorBool all_one(m); - for(size_t i = 0; i < m; i++) - all_one[i] = true; - - // set version of sparsity for n by n idendity matrix - vectorBool identity(n * n); - for(size_t j = 0; j < n; j++) - { for(size_t i = 0; i < n; i++) - identity[ i * n + j ] = (i == j); - } - - // compute sparsity pattern for H(x) = sum_i f_i(x)^{(2)} - bool transpose = false; - bool dependency = false; - f_.ForSparseJac(n, identity, transpose, dependency); - hes_sparse_bool_ = f_.RevSparseHes(n, all_one, transpose); - CPPAD_ASSERT_UNKNOWN( hes_sparse_bool_.size() == n * n ); - // - // drop the forward sparsity results from f_ - f_.size_forward_bool(0); - CPPAD_ASSERT_UNKNOWN( f_.size_forward_bool() == 0 ); - CPPAD_ASSERT_UNKNOWN( f_.size_forward_set() == 0 ); - } - // ------------------------------------------------------------------------ - /*! - Link from user_atomic to forward sparse Jacobian pack and bool - - \copydetails atomic_base::for_sparse_jac - */ - template - bool for_sparse_jac( - size_t q , - const sparsity_type& r , - sparsity_type& s ) - { // during user sparsity calculations - size_t m = f_.Range(); - size_t n = f_.Domain(); - if( jac_sparse_bool_.size() == 0 ) - set_jac_sparse_bool(); - if( jac_sparse_set_.n_set() != 0 ) - jac_sparse_set_.resize(0, 0); - CPPAD_ASSERT_UNKNOWN( jac_sparse_bool_.size() == m * n ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.n_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( r.size() == n * q ); - CPPAD_ASSERT_UNKNOWN( s.size() == m * q ); - // - bool ok = true; - for(size_t i = 0; i < m; i++) - { for(size_t k = 0; k < q; k++) - s[i * q + k] = false; - } - // sparsity for s = jac_sparse_bool_ * r - for(size_t i = 0; i < m; i++) - { // compute row i of the return pattern - for(size_t j = 0; j < n; j++) - { if( jac_sparse_bool_[ i * n + j] ) - { for(size_t k = 0; k < q; k++) - // s[i * q + k] |= r[j * q + k ]; - s[i * q + k] = bool(s[i * q + k]) | bool(r[j * q + k]); - } - } - } - return ok; - } - // ------------------------------------------------------------------------ - /*! - Link from user_atomic to reverse sparse Jacobian pack and bool - - \copydetails atomic_base::rev_sparse_jac - */ - template - bool rev_sparse_jac( - size_t q , - const sparsity_type& rt , - sparsity_type& st ) - { // during user sparsity calculations - size_t m = f_.Range(); - size_t n = f_.Domain(); - if( jac_sparse_bool_.size() == 0 ) - set_jac_sparse_bool(); - if( jac_sparse_set_.n_set() != 0 ) - jac_sparse_set_.resize(0, 0); - CPPAD_ASSERT_UNKNOWN( jac_sparse_bool_.size() == m * n ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.n_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( rt.size() == m * q ); - CPPAD_ASSERT_UNKNOWN( st.size() == n * q ); - bool ok = true; - // - for(size_t j = 0; j < n; j++) - { for(size_t k = 0; k < q; k++) - st[j * q + k] = false; - } - // - // sparsity for s = r * jac_sparse_bool_ - // s^T = jac_sparse_bool_^T * r^T - for(size_t i = 0; i < m; i++) - { // i is the row index in r^T - for(size_t k = 0; k < q; k++) - { // k is column index in r^T - if( rt[i * q + k] ) - { // i is column index in jac_sparse_bool_^T - for(size_t j = 0; j < n; j++) - { if( jac_sparse_bool_[i * n + j] ) - st[j * q + k ] = true; - } - } - } - } - return ok; - } - /*! - Link from user_atomic to reverse sparse Hessian bools - - \copydetails atomic_base::rev_sparse_hes - */ - template - bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const sparsity_type& r , - const sparsity_type& u , - sparsity_type& v ) - { size_t n = f_.Domain(); - size_t m = f_.Range(); - CPPAD_ASSERT_UNKNOWN( vx.size() == n ); - CPPAD_ASSERT_UNKNOWN( s.size() == m ); - CPPAD_ASSERT_UNKNOWN( t.size() == n ); - CPPAD_ASSERT_UNKNOWN( r.size() == n * q ); - CPPAD_ASSERT_UNKNOWN( u.size() == m * q ); - CPPAD_ASSERT_UNKNOWN( v.size() == n * q ); - // - bool ok = true; - - // make sure hes_sparse_bool_ has been set - if( hes_sparse_bool_.size() == 0 ) - set_hes_sparse_bool(); - if( hes_sparse_set_.n_set() != 0 ) - hes_sparse_set_.resize(0, 0); - CPPAD_ASSERT_UNKNOWN( hes_sparse_bool_.size() == n * n ); - CPPAD_ASSERT_UNKNOWN( hes_sparse_set_.n_set() == 0 ); - - - // compute sparsity pattern for T(x) = S(x) * f'(x) - t = f_.RevSparseJac(1, s); -# ifndef NDEBUG - for(size_t j = 0; j < n; j++) - CPPAD_ASSERT_UNKNOWN( vx[j] || ! t[j] ) -# endif - - // V(x) = f'(x)^T * g''(y) * f'(x) * R + g'(y) * f''(x) * R - // U(x) = g''(y) * f'(x) * R - // S(x) = g'(y) - - // compute sparsity pattern for A(x) = f'(x)^T * U(x) - bool transpose = true; - sparsity_type a(n * q); - a = f_.RevSparseJac(q, u, transpose); - - // Need sparsity pattern for H(x) = (S(x) * f(x))''(x) * R, - // but use less efficient sparsity for f(x)''(x) * R so that - // hes_sparse_set_ can be used every time this is needed. - for(size_t i = 0; i < n; i++) - { for(size_t k = 0; k < q; k++) - v[i * q + k] = false; - for(size_t j = 0; j < n; j++) - { if( hes_sparse_bool_[i * n + j] ) - { for(size_t k = 0; k < q; k++) - // v[i * q + k] |= r[ j * q + k ]; - v[i * q + k] = bool(v[i*q + k]) | bool(r[j*q + k]); - } - } - } - - // compute sparsity pattern for V(x) = A(x) + H(x) - for(size_t i = 0; i < n; i++) - { for(size_t k = 0; k < q; k++) - // v[ i * q + k ] |= a[ i * q + k]; - v[ i * q + k ] = bool(v[ i * q + k]) | bool(a[ i * q + k]); - } - return ok; - } -public: - // ------------------------------------------------------------------------ - /*! - Constructor of a checkpoint object - - \param name [in] - is the user's name for the AD version of this atomic operation. - - \param algo [in/out] - user routine that compute AD function values - (not const because state may change during evaluation). - - \param ax [in] - argument value where algo operation sequence is taped. - - \param ay [out] - function value at specified argument value. - - \param sparsity [in] - what type of sparsity patterns are computed by this function, - pack_sparsity_enum bool_sparsity_enum, or set_sparsity_enum. - The default value is unspecified. - */ - template - checkpoint( - const char* name , - Algo& algo , - const ADVector& ax , - ADVector& ay , - option_enum sparsity = - atomic_base::pack_sparsity_enum - ) : atomic_base(name, sparsity) - { CheckSimpleVector< CppAD::AD , ADVector>(); - - // make a copy of ax because Independent modifies AD information - ADVector x_tmp(ax); - // delcare x_tmp as the independent variables - Independent(x_tmp); - // record mapping from x_tmp to ay - algo(x_tmp, ay); - // create function f_ : x -> y - f_.Dependent(ay); - // suppress checking for nan in f_ results - // (see optimize documentation for atomic functions) - f_.check_for_nan(false); - // now optimize (we expect to use this function many times). - f_.optimize(); - // now disable checking of comparison opertaions - // 2DO: add a debugging mode that checks for changes and aborts - f_.compare_change_count(0); - } - // ------------------------------------------------------------------------ - /*! - Implement the user call to atom_fun.size_var(). - */ - size_t size_var(void) - { return f_.size_var(); } - // ------------------------------------------------------------------------ - /*! - Implement the user call to atom_fun(ax, ay). - - \tparam ADVector - A simple vector class with elements of type AD. - - \param id - optional parameter which must be zero if present. - - \param ax - is the argument vector for this call, - ax.size() determines the number of arguments. - - \param ay - is the result vector for this call, - ay.size() determines the number of results. - */ - template - void operator()(const ADVector& ax, ADVector& ay, size_t id = 0) - { CPPAD_ASSERT_KNOWN( - id == 0, - "checkpoint: id is non-zero in atom_fun(ax, ay, id)" - ); - this->atomic_base::operator()(ax, ay, id); - } - // ------------------------------------------------------------------------ - /*! - Link from user_atomic to forward mode - - \copydetails atomic_base::forward - */ - virtual bool forward( - size_t p , - size_t q , - const vector& vx , - vector& vy , - const vector& tx , - vector& ty ) - { size_t n = f_.Domain(); - size_t m = f_.Range(); - // - CPPAD_ASSERT_UNKNOWN( f_.size_var() > 0 ); - CPPAD_ASSERT_UNKNOWN( tx.size() % (q+1) == 0 ); - CPPAD_ASSERT_UNKNOWN( ty.size() % (q+1) == 0 ); - CPPAD_ASSERT_UNKNOWN( n == tx.size() / (q+1) ); - CPPAD_ASSERT_UNKNOWN( m == ty.size() / (q+1) ); - bool ok = true; - // - if( vx.size() == 0 ) - { // during user forward mode - if( jac_sparse_set_.n_set() != 0 ) - jac_sparse_set_.resize(0,0); - if( jac_sparse_bool_.size() != 0 ) - jac_sparse_bool_.clear(); - // - if( hes_sparse_set_.n_set() != 0 ) - hes_sparse_set_.resize(0,0); - if( hes_sparse_bool_.size() != 0 ) - hes_sparse_bool_.clear(); - } - if( vx.size() > 0 ) - { // need Jacobian sparsity pattern to determine variable relation - // during user recording using checkpoint functions - if( sparsity() == atomic_base::set_sparsity_enum ) - { if( jac_sparse_set_.n_set() == 0 ) - set_jac_sparse_set(); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.n_set() == m ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.end() == n ); - // - for(size_t i = 0; i < m; i++) - { vy[i] = false; - jac_sparse_set_.begin(i); - size_t j = jac_sparse_set_.next_element(); - while(j < n ) - { // y[i] depends on the value of x[j] - // cast avoid Microsoft warning (should not be needed) - vy[i] |= static_cast( vx[j] ); - j = jac_sparse_set_.next_element(); - } - } - } - else - { if( jac_sparse_set_.n_set() != 0 ) - jac_sparse_set_.resize(0, 0); - if( jac_sparse_bool_.size() == 0 ) - set_jac_sparse_bool(); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.n_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_bool_.size() == m * n ); - // - for(size_t i = 0; i < m; i++) - { vy[i] = false; - for(size_t j = 0; j < n; j++) - { if( jac_sparse_bool_[ i * n + j ] ) - { // y[i] depends on the value of x[j] - // cast avoid Microsoft warning - vy[i] |= static_cast( vx[j] ); - } - } - } - } - } - ty = f_.Forward(q, tx); - - // no longer need the Taylor coefficients in f_ - // (have to reconstruct them every time) - // Hold onto sparsity pattern because it is always good. - size_t c = 0; - size_t r = 0; - f_.capacity_order(c, r); - return ok; - } - // ------------------------------------------------------------------------ - /*! - Link from user_atomic to reverse mode - - \copydetails atomic_base::reverse - */ - virtual bool reverse( - size_t q , - const vector& tx , - const vector& ty , - vector& px , - const vector& py ) - { size_t n = f_.Domain(); - size_t m = f_.Range(); - CPPAD_ASSERT_UNKNOWN( n == tx.size() / (q+1) ); - CPPAD_ASSERT_UNKNOWN( m == ty.size() / (q+1) ); - CPPAD_ASSERT_UNKNOWN( f_.size_var() > 0 ); - CPPAD_ASSERT_UNKNOWN( tx.size() % (q+1) == 0 ); - CPPAD_ASSERT_UNKNOWN( ty.size() % (q+1) == 0 ); - bool ok = true; - - // put proper forward mode coefficients in f_ -# ifdef NDEBUG - f_.Forward(q, tx); -# else - CPPAD_ASSERT_UNKNOWN( px.size() == n * (q+1) ); - CPPAD_ASSERT_UNKNOWN( py.size() == m * (q+1) ); - size_t i, j, k; - // - vector check_ty = f_.Forward(q, tx); - for(i = 0; i < m; i++) - { for(k = 0; k <= q; k++) - { j = i * (q+1) + k; - CPPAD_ASSERT_UNKNOWN( check_ty[j] == ty[j] ); - } - } -# endif - // now can run reverse mode - px = f_.Reverse(q+1, py); - - // no longer need the Taylor coefficients in f_ - // (have to reconstruct them every time) - size_t c = 0; - size_t r = 0; - f_.capacity_order(c, r); - return ok; - } - // ------------------------------------------------------------------------ - /*! - Link from user_atomic to forward sparse Jacobian pack - - \copydetails atomic_base::for_sparse_jac - */ - virtual bool for_sparse_jac( - size_t q , - const vectorBool& r , - vectorBool& s ) - { return for_sparse_jac< vectorBool >(q, r, s); - } - /*! - Link from user_atomic to forward sparse Jacobian bool - - \copydetails atomic_base::for_sparse_jac - */ - virtual bool for_sparse_jac( - size_t q , - const vector& r , - vector& s ) - { return for_sparse_jac< vector >(q, r, s); - } - /*! - Link from user_atomic to forward sparse Jacobian sets - - \copydetails atomic_base::for_sparse_jac - */ - virtual bool for_sparse_jac( - size_t q , - const vector< std::set >& r , - vector< std::set >& s ) - { // during user sparsity calculations - size_t m = f_.Range(); - size_t n = f_.Domain(); - if( jac_sparse_bool_.size() != 0 ) - jac_sparse_bool_.clear(); - if( jac_sparse_set_.n_set() == 0 ) - set_jac_sparse_set(); - CPPAD_ASSERT_UNKNOWN( jac_sparse_bool_.size() == 0 ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.n_set() == m ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.end() == n ); - CPPAD_ASSERT_UNKNOWN( r.size() == n ); - CPPAD_ASSERT_UNKNOWN( s.size() == m ); - - bool ok = true; - for(size_t i = 0; i < m; i++) - s[i].clear(); - - // sparsity for s = jac_sparse_set_ * r - for(size_t i = 0; i < m; i++) - { // compute row i of the return pattern - jac_sparse_set_.begin(i); - size_t j = jac_sparse_set_.next_element(); - while(j < n ) - { std::set::const_iterator itr_j; - const std::set& r_j( r[j] ); - for(itr_j = r_j.begin(); itr_j != r_j.end(); itr_j++) - { size_t k = *itr_j; - CPPAD_ASSERT_UNKNOWN( k < q ); - s[i].insert(k); - } - j = jac_sparse_set_.next_element(); - } - } - - return ok; - } - // ------------------------------------------------------------------------ - /*! - Link from user_atomic to reverse sparse Jacobian pack - - \copydetails atomic_base::rev_sparse_jac - */ - virtual bool rev_sparse_jac( - size_t q , - const vectorBool& rt , - vectorBool& st ) - { return rev_sparse_jac< vectorBool >(q, rt, st); - } - /*! - Link from user_atomic to reverse sparse Jacobian bool - - \copydetails atomic_base::rev_sparse_jac - */ - virtual bool rev_sparse_jac( - size_t q , - const vector& rt , - vector& st ) - { return rev_sparse_jac< vector >(q, rt, st); - } - /*! - Link from user_atomic to reverse Jacobian sets - - \copydetails atomic_base::rev_sparse_jac - */ - virtual bool rev_sparse_jac( - size_t q , - const vector< std::set >& rt , - vector< std::set >& st ) - { // during user sparsity calculations - size_t m = f_.Range(); - size_t n = f_.Domain(); - if( jac_sparse_bool_.size() != 0 ) - jac_sparse_bool_.clear(); - if( jac_sparse_set_.n_set() == 0 ) - set_jac_sparse_set(); - CPPAD_ASSERT_UNKNOWN( jac_sparse_bool_.size() == 0 ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.n_set() == m ); - CPPAD_ASSERT_UNKNOWN( jac_sparse_set_.end() == n ); - CPPAD_ASSERT_UNKNOWN( rt.size() == m ); - CPPAD_ASSERT_UNKNOWN( st.size() == n ); - // - bool ok = true; - // - for(size_t j = 0; j < n; j++) - st[j].clear(); - // - // sparsity for s = r * jac_sparse_set_ - // s^T = jac_sparse_set_^T * r^T - for(size_t i = 0; i < m; i++) - { // i is the row index in r^T - std::set::const_iterator itr_i; - const std::set& r_i( rt[i] ); - for(itr_i = r_i.begin(); itr_i != r_i.end(); itr_i++) - { // k is the column index in r^T - size_t k = *itr_i; - CPPAD_ASSERT_UNKNOWN( k < q ); - // - // i is column index in jac_sparse_set^T - jac_sparse_set_.begin(i); - size_t j = jac_sparse_set_.next_element(); - while( j < n ) - { // j is row index in jac_sparse_set^T - st[j].insert(k); - j = jac_sparse_set_.next_element(); - } - } - } - - return ok; - } - // ------------------------------------------------------------------------ - /*! - Link from user_atomic to reverse sparse Hessian pack - - \copydetails atomic_base::rev_sparse_hes - */ - virtual bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const vectorBool& r , - const vectorBool& u , - vectorBool& v ) - { return rev_sparse_hes< vectorBool >(vx, s, t, q, r, u, v); - } - /*! - Link from user_atomic to reverse sparse Hessian bool - - \copydetails atomic_base::rev_sparse_hes - */ - virtual bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const vector& r , - const vector& u , - vector& v ) - { return rev_sparse_hes< vector >(vx, s, t, q, r, u, v); - } - /*! - Link from user_atomic to reverse sparse Hessian sets - - \copydetails atomic_base::rev_sparse_hes - */ - virtual bool rev_sparse_hes( - const vector& vx , - const vector& s , - vector& t , - size_t q , - const vector< std::set >& r , - const vector< std::set >& u , - vector< std::set >& v ) - { size_t n = f_.Domain(); - size_t m = f_.Range(); - CPPAD_ASSERT_UNKNOWN( vx.size() == n ); - CPPAD_ASSERT_UNKNOWN( s.size() == m ); - CPPAD_ASSERT_UNKNOWN( t.size() == n ); - CPPAD_ASSERT_UNKNOWN( r.size() == n ); - CPPAD_ASSERT_UNKNOWN( u.size() == m ); - CPPAD_ASSERT_UNKNOWN( v.size() == n ); - // - bool ok = true; - - // make sure hes_sparse_set_ has been set - if( hes_sparse_bool_.size() != 0 ) - hes_sparse_bool_.clear(); - if( hes_sparse_set_.n_set() == 0 ) - set_hes_sparse_set(); - CPPAD_ASSERT_UNKNOWN( hes_sparse_bool_.size() == 0 ); - CPPAD_ASSERT_UNKNOWN( hes_sparse_set_.n_set() == n ); - CPPAD_ASSERT_UNKNOWN( hes_sparse_set_.end() == n ); - - // compute sparsity pattern for T(x) = S(x) * f'(x) - t = f_.RevSparseJac(1, s); -# ifndef NDEBUG - for(size_t j = 0; j < n; j++) - CPPAD_ASSERT_UNKNOWN( vx[j] || ! t[j] ) -# endif - - // V(x) = f'(x)^T * g''(y) * f'(x) * R + g'(y) * f''(x) * R - // U(x) = g''(y) * f'(x) * R - // S(x) = g'(y) - - // compute sparsity pattern for A(x) = f'(x)^T * U(x) - // 2DO: change a to use INTERNAL_SPARSE_SET - bool transpose = true; - vector< std::set > a(n); - a = f_.RevSparseJac(q, u, transpose); - - // Need sparsity pattern for H(x) = (S(x) * f(x))''(x) * R, - // but use less efficient sparsity for f(x)''(x) * R so that - // hes_sparse_set_ can be used every time this is needed. - for(size_t i = 0; i < n; i++) - { v[i].clear(); - hes_sparse_set_.begin(i); - size_t j = hes_sparse_set_.next_element(); - while( j < n ) - { std::set::const_iterator itr_j; - const std::set& r_j( r[j] ); - for(itr_j = r_j.begin(); itr_j != r_j.end(); itr_j++) - { size_t k = *itr_j; - v[i].insert(k); - } - j = hes_sparse_set_.next_element(); - } - } - // compute sparsity pattern for V(x) = A(x) + H(x) - std::set::const_iterator itr; - for(size_t i = 0; i < n; i++) - { for(itr = a[i].begin(); itr != a[i].end(); itr++) - { size_t j = *itr; - CPPAD_ASSERT_UNKNOWN( j < q ); - v[i].insert(j); - } - } - - return ok; - } -}; - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/color_general.hpp b/ct_core/include/ct/external/cppad/local/color_general.hpp deleted file mode 100644 index 24aba6abe..000000000 --- a/ct_core/include/ct/external/cppad/local/color_general.hpp +++ /dev/null @@ -1,288 +0,0 @@ -// $Id: color_general.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_COLOR_GENERAL_HPP -# define CPPAD_COLOR_GENERAL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file color_general.hpp -Coloring algorithm for a general sparse matrix. -*/ -// -------------------------------------------------------------------------- -/*! -Determine which rows of a general sparse matrix can be computed together; -i.e., do not have non-zero entries with the same column index. - -\tparam VectorSize -is a simple vector class with elements of type size_t. - -\tparam VectorSet -is an unspecified type with the exception that it must support the -operations under pattern and the following operations where -p is a VectorSet object: -\n -VectorSet p -Constructs a new vector of sets object. -\n -p.resize(ns, ne) -resizes \c p to \c ns sets with elements between zero \c ne. -All of the \c ns sets are initially empty. -\n -p.add_element(s, e) -add element \c e to set with index \c s. - -\param pattern [in] -Is a representation of the sparsity pattern for the matrix. -Note that color_general does not change the values in pattern, -but it is not const because its iterator facility modifies some of its -internal data. -\n -m = pattern.n_set() -\n -sets \c m to the number of rows in the sparse matrix. -All of the row indices are less than this value. -\n -n = pattern.end() -\n -sets \c n to the number of columns in the sparse matrix. -All of the column indices are less than this value. -\n -pattern.begin(i) -instructs the iterator facility to start iterating over -columns in the i-th row of the sparsity pattern. -\n -j = pattern.next_element() -Sets j to the next possibly non-zero column -in the row specified by the previous call to pattern.begin. -If there are no more such columns, the value -pattern.end() is returned. - -\param row [in] -is a vector specifying which row indices to compute. - -\param col [in] -is a vector, with the same size as row, -that specifies which column indices to compute. -For each valid index k, the index pair -(row[k], col[k]) must be present in the sparsity pattern. -It may be that some entries in the sparsity pattern do not need to be computed; -i.e, do not appear in the set of -(row[k], col[k]) entries. - -\param color [out] -is a vector with size m. -The input value of its elements does not matter. -Upon return, it is a coloring for the rows of the sparse matrix. -\n -\n -If for some i, color[i] == m, then -the i-th row does not appear in the vector row. -Otherwise, color[i] < m. -\n -\n -Suppose two differen rows, i != r have the same color and -column index j is such that both of the pairs -(i, j) and (r, j) appear in the sparsity pattern. -It follows that neither of these pairs appear in the set of -(row[k], col[k]) entries. -\n -\n -This routine tries to minimize, with respect to the choice of colors, -the maximum, with respct to k, of color[ row[k] ] -(not counting the indices k for which row[k] == m). -*/ -template -void color_general_cppad( - VectorSet& pattern , - const VectorSize& row , - const VectorSize& col , - CppAD::vector& color ) -{ size_t i, j, k, ell, r; - - size_t K = row.size(); - size_t m = pattern.n_set(); - size_t n = pattern.end(); - - CPPAD_ASSERT_UNKNOWN( size_t( col.size() ) == K ); - CPPAD_ASSERT_UNKNOWN( size_t( color.size() ) == m ); - - // We define the set of rows, columns, and pairs that appear - // by the set ( row[k], col[k] ) for k = 0, ... , K-1. - - // initialize rows that appear - CppAD::vector row_appear(m); - for(i = 0; i < m; i++) - row_appear[i] = false; - - // rows and columns that appear - VectorSet c2r_appear, r2c_appear; - c2r_appear.resize(n, m); - r2c_appear.resize(m, n); - for(k = 0; k < K; k++) - { CPPAD_ASSERT_UNKNOWN( pattern.is_element(row[k], col[k]) ); - row_appear[ row[k] ] = true; - c2r_appear.add_element(col[k], row[k]); - r2c_appear.add_element(row[k], col[k]); - } - - // for each column, which rows are non-zero and do not appear - VectorSet not_appear; - not_appear.resize(n, m); - for(i = 0; i < m; i++) - { pattern.begin(i); - j = pattern.next_element(); - while( j != pattern.end() ) - { if( ! c2r_appear.is_element(j , i) ) - not_appear.add_element(j, i); - j = pattern.next_element(); - } - } - - // initial coloring - color.resize(m); - ell = 0; - for(i = 0; i < m; i++) - { if( row_appear[i] ) - color[i] = ell++; - else color[i] = m; - } - /* - See GreedyPartialD2Coloring Algorithm Section 3.6.2 of - Graph Coloring in Optimization Revisited by - Assefaw Gebremedhin, Fredrik Maane, Alex Pothen - - The algorithm above was modified (by Brad Bell) to take advantage of the - fact that only the entries (subset of the sparsity pattern) specified by - row and col need to be computed. - */ - CppAD::vector forbidden(m); - for(i = 1; i < m; i++) // for each row that appears - if( color[i] < m ) - { - // initial all colors as ok for this row - // (value of forbidden for ell > initial color[i] does not matter) - for(ell = 0; ell <= color[i]; ell++) - forbidden[ell] = false; - - // ----------------------------------------------------- - // Forbid colors for which this row would destroy results: - // - // for each column that is non-zero for this row - pattern.begin(i); - j = pattern.next_element(); - while( j != pattern.end() ) - { // for each row that appears with this column - c2r_appear.begin(j); - r = c2r_appear.next_element(); - while( r != c2r_appear.end() ) - { // if this is not the same row, forbid its color - if( (r < i) & (color[r] < m) ) - forbidden[ color[r] ] = true; - r = c2r_appear.next_element(); - } - j = pattern.next_element(); - } - - - // ----------------------------------------------------- - // Forbid colors that destroy results needed for this row. - // - // for each column that appears with this row - r2c_appear.begin(i); - j = r2c_appear.next_element(); - while( j != r2c_appear.end() ) - { // For each row that is non-zero for this column - // (the appear rows have already been checked above). - not_appear.begin(j); - r = not_appear.next_element(); - while( r != not_appear.end() ) - { // if this is not the same row, forbid its color - if( (r < i) & (color[r] < m) ) - forbidden[ color[r] ] = true; - r = not_appear.next_element(); - } - j = r2c_appear.next_element(); - } - - // pick the color with smallest index - ell = 0; - while( forbidden[ell] ) - { ell++; - CPPAD_ASSERT_UNKNOWN( ell <= color[i] ); - } - color[i] = ell; - } - return; -} - -# if CPPAD_HAS_COLPACK -/*! -Colpack version of determining which rows of a sparse matrix -can be computed together. - -\copydetails color_general -*/ -template -void color_general_colpack( - VectorSet& pattern , - const VectorSize& row , - const VectorSize& col , - CppAD::vector& color ) -{ size_t i, j, k; - size_t m = pattern.n_set(); - size_t n = pattern.end(); - - // Determine number of non-zero entries in each row - CppAD::vector n_nonzero(m); - size_t n_nonzero_total = 0; - for(i = 0; i < m; i++) - { n_nonzero[i] = 0; - pattern.begin(i); - j = pattern.next_element(); - while( j != pattern.end() ) - { n_nonzero[i]++; - j = pattern.next_element(); - } - n_nonzero_total += n_nonzero[i]; - } - - // Allocate memory and fill in Adolc sparsity pattern - CppAD::vector adolc_pattern(m); - CppAD::vector adolc_memory(m + n_nonzero_total); - size_t i_memory = 0; - for(i = 0; i < m; i++) - { adolc_pattern[i] = adolc_memory.data() + i_memory; - adolc_pattern[i][0] = n_nonzero[i]; - pattern.begin(i); - j = pattern.next_element(); - k = 1; - while(j != pattern.end() ) - { adolc_pattern[i][k++] = j; - j = pattern.next_element(); - } - CPPAD_ASSERT_UNKNOWN( k == 1 + n_nonzero[i] ); - i_memory += k; - } - CPPAD_ASSERT_UNKNOWN( i_memory == m + n_nonzero_total ); - - // Must use an external routine for this part of the calculation because - // ColPack/ColPackHeaders.h has as 'using namespace std' at global level. - cppad_colpack_general(color, m, n, adolc_pattern); - - return; -} -# endif // CPPAD_HAS_COLPACK - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/color_symmetric.hpp b/ct_core/include/ct/external/cppad/local/color_symmetric.hpp deleted file mode 100644 index 4c8b30db9..000000000 --- a/ct_core/include/ct/external/cppad/local/color_symmetric.hpp +++ /dev/null @@ -1,333 +0,0 @@ -// $Id: color_symmetric.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_COLOR_SYMMETRIC_HPP -# define CPPAD_COLOR_SYMMETRIC_HPP - -# include - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/*! -\file color_symmetric.hpp -Coloring algorithm for a symmetric sparse matrix. -*/ -// -------------------------------------------------------------------------- -/*! -CppAD algorithm for determining which rows of a symmetric sparse matrix can be -computed together. - -\tparam VectorSize -is a simple vector class with elements of type size_t. - -\tparam VectorSet -is an unspecified type with the exception that it must support the -operations under pattern and the following operations where -p is a VectorSet object: -\n -VectorSet p -Constructs a new vector of sets object. -\n -p.resize(ns, ne) -resizes \c p to ns sets with elements between zero and \c ne. -All of the sets are initially empty. -\n -p.add_element(s, e) -add element \c e to set with index \c s. - -\param pattern [in] -Is a representation of the sparsity pattern for the matrix. -Note that color_symmetric does not change the values in pattern, -but it is not const because its iterator facility modifies some of its -internal data. -\n -m = pattern.n_set() -\n -sets m to the number of rows (and columns) in the sparse matrix. -All of the row indices are less than this value. -\n -n = pattern.end() -\n -sets n to the number of columns in the sparse matrix -(which must be equal to the number of rows). -All of the column indices are less than this value. -\n -pattern.begin(i) -instructs the iterator facility to start iterating over -columns in the i-th row of the sparsity pattern. -\n -j = pattern.next_element() -Sets j to the next possibly non-zero column -in the row specified by the previous call to pattern.begin. -If there are no more such columns, the value -pattern.end() is returned. - -\param row [in/out] -is a vector specifying which row indices to compute. - -\param col [in/out] -is a vector, with the same size as row, -that specifies which column indices to compute. -\n -\n -Input: -For each valid index \c k, the index pair -(row[k], col[k]) must be present in the sparsity pattern. -It may be that some entries in the sparsity pattern do not need to be computed; -i.e, do not appear in the set of -(row[k], col[k]) entries. -\n -\n -Output: -On output, some of row and column indices may have been swapped -\code - std::swap( row[k], col[k] ) -\endcode -So the the the color for row[k] can be used to compute entry -(row[k], col[k]). - -\param color [out] -is a vector with size m. -The input value of its elements does not matter. -Upon return, it is a coloring for the rows of the sparse matrix. -Note that if color[i] == m, then ther is no index k for which -row[k] == i (for the return value of row). -\n -\n -Fix any (i, j) in the sparsity pattern. -Suppose that there is a row index i1 with -i1 != i, color[i1] == color[i] and (i1, j) is in the sparsity pattern. -If follows that for all j1 with -j1 != j and color[j1] == color[j], -(j1, i ) is not in the sparsity pattern. -\n -\n -This routine tries to minimize, with respect to the choice of colors, -the maximum, with respect to k, of color[ row[k] ]. -*/ -template -void color_symmetric_cppad( - VectorSet& pattern , - CppAD::vector& row , - CppAD::vector& col , - CppAD::vector& color ) -{ size_t o1, o2, i1, i2, j1, j2, k1, c1, c2; - - size_t K = row.size(); - size_t m = pattern.n_set(); - CPPAD_ASSERT_UNKNOWN( m == pattern.end() ); - CPPAD_ASSERT_UNKNOWN( color.size() == m ); - CPPAD_ASSERT_UNKNOWN( col.size() == K ); - - // row, column pairs that appear in ( row[k], col[k] ) - CppAD::vector< std::set > pair_needed(m); - std::set::iterator itr1, itr2; - for(k1 = 0; k1 < K; k1++) - { CPPAD_ASSERT_UNKNOWN( pattern.is_element(row[k1], col[k1]) ); - pair_needed[ row[k1] ].insert( col[k1] ); - pair_needed[ col[k1] ].insert( row[k1] ); - } - - // order the rows decending by number of pairs needed - CppAD::vector key(m), order2row(m); - for(i1 = 0; i1 < m; i1++) - { CPPAD_ASSERT_UNKNOWN( pair_needed[i1].size() <= m ); - key[i1] = m - pair_needed[i1].size(); - } - CppAD::index_sort(key, order2row); - - // mapping from order index to row index - CppAD::vector row2order(m); - for(o1 = 0; o1 < m; o1++) - row2order[ order2row[o1] ] = o1; - - // initial coloring - color.resize(m); - c1 = 0; - for(o1 = 0; o1 < m; o1++) - { i1 = order2row[o1]; - if( pair_needed[i1].empty() ) - color[i1] = m; - else - color[i1] = c1++; - } - - // which colors are forbidden for this row - CppAD::vector forbidden(m); - - // must start with row zero so that we remove results computed for it - for(o1 = 0; o1 < m; o1++) // for each row that appears (in order) - if( color[ order2row[o1] ] < m ) - { i1 = order2row[o1]; - c1 = color[i1]; - - // initial all colors as ok for this row - // (value of forbidden for c > c1 does not matter) - for(c2 = 0; c2 <= c1; c2++) - forbidden[c2] = false; - - // ----------------------------------------------------- - // Forbid grouping with rows that would destroy results that are - // needed for this row. - itr1 = pair_needed[i1].begin(); - while( itr1 != pair_needed[i1].end() ) - { // entry (i1, j1) is needed for this row - j1 = *itr1; - - // Forbid rows i2 != i1 that have non-zero sparsity at (i2, j1). - // Note that this is the same as non-zero sparsity at (j1, i2) - pattern.begin(j1); - i2 = pattern.next_element(); - while( i2 != pattern.end() ) - { c2 = color[i2]; - if( c2 < c1 ) - forbidden[c2] = true; - i2 = pattern.next_element(); - } - itr1++; - } - // ----------------------------------------------------- - // Forbid grouping with rows that this row would destroy results for - for(o2 = 0; o2 < o1; o2++) - { i2 = order2row[o2]; - c2 = color[i2]; - itr2 = pair_needed[i2].begin(); - while( itr2 != pair_needed[i2].end() ) - { j2 = *itr2; - // row i2 needs pair (i2, j2). - // Forbid grouping with i1 if (i1, j2) has non-zero sparsity - if( pattern.is_element(i1, j2) ) - forbidden[c2] = true; - itr2++; - } - } - - // pick the color with smallest index - c2 = 0; - while( forbidden[c2] ) - { c2++; - CPPAD_ASSERT_UNKNOWN( c2 <= c1 ); - } - color[i1] = c2; - - // no longer need results that are computed by this row - itr1 = pair_needed[i1].begin(); - while( itr1 != pair_needed[i1].end() ) - { j1 = *itr1; - if( row2order[j1] > o1 ) - { itr2 = pair_needed[j1].find(i1); - if( itr2 != pair_needed[j1].end() ) - { pair_needed[j1].erase(itr2); - if( pair_needed[j1].empty() ) - color[j1] = m; - } - } - itr1++; - } - } - - // determine which sparsity entries need to be reflected - for(k1 = 0; k1 < row.size(); k1++) - { i1 = row[k1]; - j1 = col[k1]; - itr1 = pair_needed[i1].find(j1); - if( itr1 == pair_needed[i1].end() ) - { row[k1] = j1; - col[k1] = i1; -# ifndef NDEBUG - itr1 = pair_needed[j1].find(i1); - CPPAD_ASSERT_UNKNOWN( itr1 != pair_needed[j1].end() ); -# endif - } - } - return; -} - -// -------------------------------------------------------------------------- -/*! -Colpack algorithm for determining which rows of a symmetric sparse matrix -can be computed together. - -\copydetails color_symmetric_cppad -*/ -template -void color_symmetric_colpack( - VectorSet& pattern , - CppAD::vector& row , - CppAD::vector& col , - CppAD::vector& color ) -{ -# if ! CPPAD_HAS_COLPACK - CPPAD_ASSERT_UNKNOWN(false); - return; -# else - size_t i, j, k; - size_t m = pattern.n_set(); - CPPAD_ASSERT_UNKNOWN( m == pattern.end() ); - CPPAD_ASSERT_UNKNOWN( row.size() == col.size() ); - - // Determine number of non-zero entries in each row - CppAD::vector n_nonzero(m); - size_t n_nonzero_total = 0; - for(i = 0; i < m; i++) - { n_nonzero[i] = 0; - pattern.begin(i); - j = pattern.next_element(); - while( j != pattern.end() ) - { n_nonzero[i]++; - j = pattern.next_element(); - } - n_nonzero_total += n_nonzero[i]; - } - - // Allocate memory and fill in Adolc sparsity pattern - CppAD::vector adolc_pattern(m); - CppAD::vector adolc_memory(m + n_nonzero_total); - size_t i_memory = 0; - for(i = 0; i < m; i++) - { adolc_pattern[i] = adolc_memory.data() + i_memory; - adolc_pattern[i][0] = n_nonzero[i]; - pattern.begin(i); - j = pattern.next_element(); - k = 1; - while(j != pattern.end() ) - { adolc_pattern[i][k++] = j; - j = pattern.next_element(); - } - CPPAD_ASSERT_UNKNOWN( k == 1 + n_nonzero[i] ); - i_memory += k; - } - CPPAD_ASSERT_UNKNOWN( i_memory == m + n_nonzero_total ); - - // Must use an external routine for this part of the calculation because - // ColPack/ColPackHeaders.h has as 'using namespace std' at global level. - cppad_colpack_symmetric(color, m, adolc_pattern); - - // determine which sparsity entries need to be reflected - size_t i1, i2, j1, j2, k1, k2; - for(k1 = 0; k1 < row.size(); k1++) - { i1 = row[k1]; - j1 = col[k1]; - bool reflect = false; - for(i2 = 0; i2 < m; i2++) if( (i1 != i2) & (color[i1]==color[i2]) ) - { for(k2 = 1; k2 <= adolc_pattern[i2][0]; k2++) - { j2 = adolc_pattern[i2][k2]; - reflect |= (j1 == j2); - } - } - if( reflect ) - { row[k1] = j1; - col[k1] = i1; - } - } - return; -# endif // CPPAD_HAS_COLPACK -} - -# endif diff --git a/ct_core/include/ct/external/cppad/local/comp_op.hpp b/ct_core/include/ct/external/cppad/local/comp_op.hpp deleted file mode 100644 index 751d745a0..000000000 --- a/ct_core/include/ct/external/cppad/local/comp_op.hpp +++ /dev/null @@ -1,305 +0,0 @@ -// $Id: comp_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_COMP_OP_HPP -# define CPPAD_COMP_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file comp_op.hpp -Zero order forward mode check how many comparisons changed. -*/ - -// -------------------------------- <= ----------------------------------- -/*! -Zero order forward mode comparison check that left <= right - -\param count -It the condition is not true, ths counter is incremented by one. - -\param arg -parameter[ arg[0] ] is the left operand and -taylor[ arg[1] * cap_order + 0 ] is the zero order Taylor coefficient -for the right operand. - -\param parameter -vector of parameter values. - -\param cap_order -number of Taylor coefficients allocated for each variable - -\param taylor -vector of taylor coefficients. -*/ -template -inline void forward_lepv_op_0( - size_t& count , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(LepvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(LepvOp) == 0 ); - - // Taylor coefficients corresponding to arguments and result - Base x = parameter[ arg[0] ]; - Base* y = taylor + arg[1] * cap_order; - - count += GreaterThanZero(x - y[0]); -} -/*! -Zero order forward mode comparison check that left <= right - -\param count -It the condition is not true, ths counter is incremented by one. - -\param arg -taylor[ arg[0] * cap_order + 0 ] is the zero order Taylor coefficient -for the left operand and parameter[ arg[1] ] is the right operand - -\param parameter -vector of parameter values. - -\param cap_order -number of Taylor coefficients allocated for each variable - -\param taylor -vector of taylor coefficients. -*/ -template -inline void forward_levp_op_0( - size_t& count , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(LevpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(LevpOp) == 0 ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base y = parameter[ arg[1] ]; - - count += GreaterThanZero(x[0] - y); -} -/*! -Zero order forward mode comparison check that left <= right - -\param count -It the condition is not true, ths counter is incremented by one. - -\param arg -taylor[ arg[0] * cap_order + 0 ] is the zero order Taylor coefficient -for the left operand and -taylor[ arg[1] * cap_order + 0 ] is the zero order Taylor coefficient -for the right operand. - -\param parameter -vector of parameter values. - -\param cap_order -number of Taylor coefficients allocated for each variable - -\param taylor -vector of taylor coefficients. -*/ -template -inline void forward_levv_op_0( - size_t& count , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(LevvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(LevvOp) == 0 ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - - count += GreaterThanZero(x[0] - y[0]); -} -// ------------------------------- < ------------------------------------- -/*! -Zero order forward mode comparison check that left < right - -\copydetails forward_lepv_op_0 -*/ -template -inline void forward_ltpv_op_0( - size_t& count , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(LtpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(LtpvOp) == 0 ); - - // Taylor coefficients corresponding to arguments and result - Base x = parameter[ arg[0] ]; - Base* y = taylor + arg[1] * cap_order; - - count += GreaterThanOrZero(x - y[0]); -} -/*! -Zero order forward mode comparison check that left < right - -\copydetails forward_levp_op_0 -*/ -template -inline void forward_ltvp_op_0( - size_t& count , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(LtvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(LtvpOp) == 0 ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base y = parameter[ arg[1] ]; - - count += GreaterThanOrZero(x[0] - y); -} -/*! -Zero order forward mode comparison check that left < right - -\copydetails forward_levv_op_0 -*/ -template -inline void forward_ltvv_op_0( - size_t& count , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(LtvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(LtvvOp) == 0 ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - - count += GreaterThanOrZero(x[0] - y[0]); -} -// ------------------------------ == ------------------------------------- -/*! -Zero order forward mode comparison check that left == right - -\copydetails forward_lepv_op_0 -*/ -template -inline void forward_eqpv_op_0( - size_t& count , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(EqpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(EqpvOp) == 0 ); - - // Taylor coefficients corresponding to arguments and result - Base x = parameter[ arg[0] ]; - Base* y = taylor + arg[1] * cap_order; - - count += (x != y[0]); -} -/*! -Zero order forward mode comparison check that left == right - -\copydetails forward_levv_op_0 -*/ -template -inline void forward_eqvv_op_0( - size_t& count , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(EqvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(EqvvOp) == 0 ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - - count += (x[0] != y[0]); -} -// -------------------------------- != ----------------------------------- -/*! -Zero order forward mode comparison check that left != right - -\copydetails forward_lepv_op_0 -*/ -template -inline void forward_nepv_op_0( - size_t& count , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(NepvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(NepvOp) == 0 ); - - // Taylor coefficients corresponding to arguments and result - Base x = parameter[ arg[0] ]; - Base* y = taylor + arg[1] * cap_order; - - count += (x == y[0]); -} -/*! -Zero order forward mode comparison check that left != right - -\copydetails forward_levv_op_0 -*/ -template -inline void forward_nevv_op_0( - size_t& count , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(NevvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(NevvOp) == 0 ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - - count += (x[0] == y[0]); -} - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/compare.hpp b/ct_core/include/ct/external/cppad/local/compare.hpp deleted file mode 100644 index 17633f111..000000000 --- a/ct_core/include/ct/external/cppad/local/compare.hpp +++ /dev/null @@ -1,416 +0,0 @@ -// $Id: compare.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_COMPARE_HPP -# define CPPAD_COMPARE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin Compare$$ -$spell - cos - Op - bool - const -$$ - - - -$section AD Binary Comparison Operators$$ -$mindex compare < <= > >= == !=$$ - - -$head Syntax$$ - -$icode%b% = %x% %Op% %y%$$ - - -$head Purpose$$ -Compares two operands where one of the operands is an -$codei%AD<%Base%>%$$ object. -The comparison has the same interpretation as for -the $icode Base$$ type. - - -$head Op$$ -The operator $icode Op$$ is one of the following: -$table -$bold Op$$ $pre $$ $cnext $bold Meaning$$ $rnext -$code <$$ $cnext is $icode x$$ less than $icode y$$ $rnext -$code <=$$ $cnext is $icode x$$ less than or equal $icode y$$ $rnext -$code >$$ $cnext is $icode x$$ greater than $icode y$$ $rnext -$code >=$$ $cnext is $icode x$$ greater than or equal $icode y$$ $rnext -$code ==$$ $cnext is $icode x$$ equal to $icode y$$ $rnext -$code !=$$ $cnext is $icode x$$ not equal to $icode y$$ -$tend - -$head x$$ -The operand $icode x$$ has prototype -$codei% - const %Type% &%x% -%$$ -where $icode Type$$ is $codei%AD<%Base%>%$$, $icode Base$$, or $code int$$. - -$head y$$ -The operand $icode y$$ has prototype -$codei% - const %Type% &%y% -%$$ -where $icode Type$$ is $codei%AD<%Base%>%$$, $icode Base$$, or $code int$$. - -$head b$$ -The result $icode b$$ has type -$codei% - bool %b% -%$$ - -$head Operation Sequence$$ -The result of this operation is a $code bool$$ value -(not an $cref/AD of Base/glossary/AD of Base/$$ object). -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. -$pre - -$$ -For example, suppose -$icode x$$ and $icode y$$ are $codei%AD<%Base%>%$$ objects, -the tape corresponding to $codei%AD<%Base%>%$$ is recording, -$icode b$$ is true, -and the subsequent code is -$codei% - if( %b% ) - %y% = cos(%x%); - else %y% = sin(%x%); -%$$ -only the assignment $icode%y% = cos(%x%)%$$ is recorded on the tape -(if $icode x$$ is a $cref/parameter/glossary/Parameter/$$, -nothing is recorded). -The $cref CompareChange$$ function can yield -some information about changes in comparison operation results. -You can use $cref CondExp$$ to obtain comparison operations -that depends on the -$cref/independent variable/glossary/Tape/Independent Variable/$$ -values with out re-taping the AD sequence of operations. - -$head Assumptions$$ -If one of the $icode Op$$ operators listed above -is used with an $codei%AD<%Base%>%$$ object, -it is assumed that the same operator is supported by the base type -$icode Base$$. - -$head Example$$ -$children% - example/compare.cpp -%$$ -The file -$cref compare.cpp$$ -contains an example and test of these operations. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ -// BEGIN CppAD namespace -namespace CppAD { - -// -------------------------------- < -------------------------- -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool operator < (const AD &left , const AD &right) -{ bool result = (left.value_ < right.value_); - bool var_left = Variable(left); - bool var_right = Variable(right); - - ADTape *tape = CPPAD_NULL; - if( var_left ) - { tape = left.tape_this(); - if( var_right ) - { if( result ) - { tape->Rec_.PutOp(LtvvOp); - tape->Rec_.PutArg(left.taddr_, right.taddr_); - } - else - { tape->Rec_.PutOp(LevvOp); - tape->Rec_.PutArg(right.taddr_, left.taddr_); - } - } - else - { addr_t arg1 = tape->Rec_.PutPar(right.value_); - if( result ) - { tape->Rec_.PutOp(LtvpOp); - tape->Rec_.PutArg(left.taddr_, arg1); - } - else - { tape->Rec_.PutOp(LepvOp); - tape->Rec_.PutArg(arg1, left.taddr_); - } - } - } - else if ( var_right ) - { tape = right.tape_this(); - addr_t arg0 = tape->Rec_.PutPar(left.value_); - if( result ) - { tape->Rec_.PutOp(LtpvOp); - tape->Rec_.PutArg(arg0, right.taddr_); - } - else - { tape->Rec_.PutOp(LevpOp); - tape->Rec_.PutArg(right.taddr_, arg0); - } - } - - return result; -} -// convert other cases into the case above -CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(<) - -// -------------------------------- <= ------------------------- -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool operator <= (const AD &left , const AD &right) -{ bool result = (left.value_ <= right.value_); - bool var_left = Variable(left); - bool var_right = Variable(right); - - ADTape *tape = CPPAD_NULL; - if( var_left ) - { tape = left.tape_this(); - if( var_right ) - { if( result ) - { tape->Rec_.PutOp(LevvOp); - tape->Rec_.PutArg(left.taddr_, right.taddr_); - } - else - { tape->Rec_.PutOp(LtvvOp); - tape->Rec_.PutArg(right.taddr_, left.taddr_); - } - } - else - { addr_t arg1 = tape->Rec_.PutPar(right.value_); - if( result ) - { tape->Rec_.PutOp(LevpOp); - tape->Rec_.PutArg(left.taddr_, arg1); - } - else - { tape->Rec_.PutOp(LtpvOp); - tape->Rec_.PutArg(arg1, left.taddr_); - } - } - } - else if ( var_right ) - { tape = right.tape_this(); - addr_t arg0 = tape->Rec_.PutPar(left.value_); - if( result ) - { tape->Rec_.PutOp(LepvOp); - tape->Rec_.PutArg(arg0, right.taddr_); - } - else - { tape->Rec_.PutOp(LtvpOp); - tape->Rec_.PutArg(right.taddr_, arg0); - } - } - - return result; -} -// convert other cases into the case above -CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(<=) - -// -------------------------------- > -------------------------- -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool operator > (const AD &left , const AD &right) -{ bool result = (left.value_ > right.value_); - bool var_left = Variable(left); - bool var_right = Variable(right); - - ADTape *tape = CPPAD_NULL; - if( var_left ) - { tape = left.tape_this(); - if( var_right ) - { if( result ) - { tape->Rec_.PutOp(LtvvOp); - tape->Rec_.PutArg(right.taddr_, left.taddr_); - } - else - { tape->Rec_.PutOp(LevvOp); - tape->Rec_.PutArg(left.taddr_, right.taddr_); - } - } - else - { addr_t arg1 = tape->Rec_.PutPar(right.value_); - if( result ) - { tape->Rec_.PutOp(LtpvOp); - tape->Rec_.PutArg(arg1, left.taddr_); - } - else - { tape->Rec_.PutOp(LevpOp); - tape->Rec_.PutArg(left.taddr_, arg1); - } - } - } - else if ( var_right ) - { tape = right.tape_this(); - addr_t arg0 = tape->Rec_.PutPar(left.value_); - if( result ) - { tape->Rec_.PutOp(LtvpOp); - tape->Rec_.PutArg(right.taddr_, arg0); - } - else - { tape->Rec_.PutOp(LepvOp); - tape->Rec_.PutArg(arg0, right.taddr_); - } - } - - return result; -} -// convert other cases into the case above -CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(>) - -// -------------------------------- >= ------------------------- -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool operator >= (const AD &left , const AD &right) -{ bool result = (left.value_ >= right.value_); - bool var_left = Variable(left); - bool var_right = Variable(right); - - ADTape *tape = CPPAD_NULL; - if( var_left ) - { tape = left.tape_this(); - if( var_right ) - { if( result ) - { tape->Rec_.PutOp(LevvOp); - tape->Rec_.PutArg(right.taddr_, left.taddr_); - } - else - { tape->Rec_.PutOp(LtvvOp); - tape->Rec_.PutArg(left.taddr_, right.taddr_); - } - } - else - { addr_t arg1 = tape->Rec_.PutPar(right.value_); - if( result ) - { tape->Rec_.PutOp(LepvOp); - tape->Rec_.PutArg(arg1, left.taddr_); - } - else - { tape->Rec_.PutOp(LtvpOp); - tape->Rec_.PutArg(left.taddr_, arg1); - } - } - } - else if ( var_right ) - { tape = right.tape_this(); - addr_t arg0 = tape->Rec_.PutPar(left.value_); - if( result ) - { tape->Rec_.PutOp(LevpOp); - tape->Rec_.PutArg(right.taddr_, arg0); - } - else - { tape->Rec_.PutOp(LtpvOp); - tape->Rec_.PutArg(arg0, right.taddr_); - } - } - - return result; -} -// convert other cases into the case above -CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(>=) - -// -------------------------------- == ------------------------- -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool operator == (const AD &left , const AD &right) -{ bool result = (left.value_ == right.value_); - bool var_left = Variable(left); - bool var_right = Variable(right); - - ADTape *tape = CPPAD_NULL; - if( var_left ) - { tape = left.tape_this(); - if( var_right ) - { tape->Rec_.PutArg(left.taddr_, right.taddr_); - if( result ) - tape->Rec_.PutOp(EqvvOp); - else - tape->Rec_.PutOp(NevvOp); - } - else - { addr_t arg1 = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(arg1, left.taddr_); - if( result ) - tape->Rec_.PutOp(EqpvOp); - else - tape->Rec_.PutOp(NepvOp); - } - } - else if ( var_right ) - { tape = right.tape_this(); - addr_t arg0 = tape->Rec_.PutPar(left.value_); - tape->Rec_.PutArg(arg0, right.taddr_); - if( result ) - tape->Rec_.PutOp(EqpvOp); - else - tape->Rec_.PutOp(NepvOp); - } - - return result; -} -// convert other cases into the case above -CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(==) - -// -------------------------------- != ------------------------- -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool operator != (const AD &left , const AD &right) -{ bool result = (left.value_ != right.value_); - bool var_left = Variable(left); - bool var_right = Variable(right); - - ADTape *tape = CPPAD_NULL; - if( var_left ) - { tape = left.tape_this(); - if( var_right ) - { tape->Rec_.PutArg(left.taddr_, right.taddr_); - if( result ) - tape->Rec_.PutOp(NevvOp); - else - tape->Rec_.PutOp(EqvvOp); - } - else - { addr_t arg1 = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(arg1, left.taddr_); - if( result ) - tape->Rec_.PutOp(NepvOp); - else - tape->Rec_.PutOp(EqpvOp); - } - } - else if ( var_right ) - { tape = right.tape_this(); - addr_t arg0 = tape->Rec_.PutPar(left.value_); - tape->Rec_.PutArg(arg0, right.taddr_); - if( result ) - tape->Rec_.PutOp(NepvOp); - else - tape->Rec_.PutOp(EqpvOp); - } - - return result; -} -// convert other cases into the case above -CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(!=) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/compute_assign.hpp b/ct_core/include/ct/external/cppad/local/compute_assign.hpp deleted file mode 100644 index 400417389..000000000 --- a/ct_core/include/ct/external/cppad/local/compute_assign.hpp +++ /dev/null @@ -1,143 +0,0 @@ -// $Id: compute_assign.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_COMPUTE_ASSIGN_HPP -# define CPPAD_COMPUTE_ASSIGN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin compute_assign$$ -$spell - Op - VecAD - const -$$ - -$section AD Computed Assignment Operators$$ -$mindex + add plus - subtract minus * multiply times / divide multiple$$ - - - - - - -$head Syntax$$ -$icode%x% %Op% %y%$$ - -$head Purpose$$ -Performs computed assignment operations -where either $icode x$$ has type -$codei%AD<%Base%>%$$. - -$head Op$$ -The operator $icode Op$$ is one of the following -$table -$bold Op$$ $cnext $bold Meaning$$ $rnext -$code +=$$ $cnext $icode x$$ is assigned $icode x$$ plus $icode y$$ $rnext -$code -=$$ $cnext $icode x$$ is assigned $icode x$$ minus $icode y$$ $rnext -$code *=$$ $cnext $icode x$$ is assigned $icode x$$ times $icode y$$ $rnext -$code /=$$ $cnext $icode x$$ is assigned $icode x$$ divided by $icode y$$ -$tend - -$head Base$$ -The type $icode Base$$ is determined by the operand $icode x$$. - -$head x$$ -The operand $icode x$$ has the following prototype -$codei% - AD<%Base%> &%x% -%$$ - -$head y$$ -The operand $icode y$$ has the following prototype -$codei% - const %Type% &%y% -%$$ -where $icode Type$$ is -$codei%VecAD<%Base%>::reference%$$, -$codei%AD<%Base%>%$$, -$icode Base$$, or -$code double$$. - -$head Result$$ -The result of this assignment -can be used as a reference to $icode x$$. -For example, if $icode z$$ has the following type -$codei% - AD<%Base%> %z% -%$$ -then the syntax -$codei% - %z% = %x% += %y% -%$$ -will compute $icode x$$ plus $icode y$$ -and then assign this value to both $icode x$$ and $icode z$$. - - -$head Operation Sequence$$ -This is an $cref/atomic/glossary/Operation/Atomic/$$ -$cref/AD of Base/glossary/AD of Base/$$ operation -and hence it is part of the current -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$children% - example/add_eq.cpp% - example/sub_eq.cpp% - example/mul_eq.cpp% - example/div_eq.cpp -%$$ - -$head Example$$ -The following files contain examples and tests of these functions. -Each test returns true if it succeeds and false otherwise. -$table -$rref AddEq.cpp$$ -$rref sub_eq.cpp$$ -$rref mul_eq.cpp$$ -$rref div_eq.cpp$$ -$tend - -$head Derivative$$ -If $latex f$$ and $latex g$$ are -$cref/Base functions/glossary/Base Function/$$ - -$subhead Addition$$ -$latex \[ - \D{[ f(x) + g(x) ]}{x} = \D{f(x)}{x} + \D{g(x)}{x} -\] $$ - -$subhead Subtraction$$ -$latex \[ - \D{[ f(x) - g(x) ]}{x} = \D{f(x)}{x} - \D{g(x)}{x} -\] $$ - -$subhead Multiplication$$ -$latex \[ - \D{[ f(x) * g(x) ]}{x} = g(x) * \D{f(x)}{x} + f(x) * \D{g(x)}{x} -\] $$ - -$subhead Division$$ -$latex \[ - \D{[ f(x) / g(x) ]}{x} = - [1/g(x)] * \D{f(x)}{x} - [f(x)/g(x)^2] * \D{g(x)}{x} -\] $$ - -$end ------------------------------------------------------------------------------ -*/ -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/local/cond_exp.hpp b/ct_core/include/ct/external/cppad/local/cond_exp.hpp deleted file mode 100644 index 3b1e02191..000000000 --- a/ct_core/include/ct/external/cppad/local/cond_exp.hpp +++ /dev/null @@ -1,360 +0,0 @@ -// $Id: cond_exp.hpp 3768 2015-12-28 18:58:35Z bradbell $ -# ifndef CPPAD_COND_EXP_HPP -# define CPPAD_COND_EXP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin CondExp$$ -$spell - Atan2 - CondExp - Taylor - std - Cpp - namespace - inline - const - abs - Rel - bool - Lt - Le - Eq - Ge - Gt -$$ - - -$section AD Conditional Expressions$$ -$mindex assign$$ - -$head Syntax$$ -$icode%result% = CondExp%Rel%(%left%, %right%, %if_true%, %if_false%)%$$ - - -$head Purpose$$ -Record, -as part of an AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$, -the conditional result -$codei% - if( %left% %Cop% %right% ) - %result% = %if_true% - else %result% = %if_false% -%$$ -The relational $icode Rel$$ and comparison operator $icode Cop$$ -above have the following correspondence: -$codei% - %Rel% Lt Le Eq Ge Gt - %Cop% < <= == >= > -%$$ -If $icode f$$ is the $cref ADFun$$ object corresponding to the -AD operation sequence, -the assignment choice for $icode result$$ -in an AD conditional expression is made each time -$cref/f.Forward/Forward/$$ is used to evaluate the zero order Taylor -coefficients with new values for the -$cref/independent variables/glossary/Tape/Independent Variable/$$. -This is in contrast to the $cref/AD comparison operators/Compare/$$ -which are boolean valued and not included in the AD operation sequence. - -$head Rel$$ -In the syntax above, the relation $icode Rel$$ represents one of the following -two characters: $code Lt$$, $code Le$$, $code Eq$$, $code Ge$$, $code Gt$$. -As in the table above, -$icode Rel$$ determines which comparison operator $icode Cop$$ is used -when comparing $icode left$$ and $icode right$$. - -$head Type$$ -These functions are defined in the CppAD namespace for arguments of -$icode Type$$ is $code float$$ , $code double$$, or any type of the form -$codei%AD<%Base%>%$$. -(Note that all four arguments must have the same type.) - -$head left$$ -The argument $icode left$$ has prototype -$codei% - const %Type%& %left% -%$$ -It specifies the value for the left side of the comparison operator. - -$head right$$ -The argument $icode right$$ has prototype -$codei% - const %Type%& %right% -%$$ -It specifies the value for the right side of the comparison operator. - -$head if_true$$ -The argument $icode if_true$$ has prototype -$codei% - const %Type%& %if_true% -%$$ -It specifies the return value if the result of the comparison is true. - -$head if_false$$ -The argument $icode if_false$$ has prototype -$codei% - const %Type%& %if_false% -%$$ -It specifies the return value if the result of the comparison is false. - -$head result$$ -The $icode result$$ has prototype -$codei% - %Type%& %if_false% -%$$ - -$head Optimize$$ -The $cref optimize$$ method will optimize conditional expressions -in the following way: -During $cref/zero order forward mode/forward_zero/$$, -once the value of the $icode left$$ and $icode right$$ have been determined, -it is known if the true or false case is required. -From this point on, values corresponding to the case that is not required -are not computed. -This optimization is done for the rest of zero order forward mode -as well as forward and reverse derivatives calculations. -There is one exception to this optimization; see -$cref/optimizing nested conditional expressions - /wish_list - /Optimizing Nested Conditional Expressions -/$$. - -$head Deprecate 2005-08-07$$ -Previous versions of CppAD used -$codei% - CondExp(%flag%, %if_true%, %if_false%) -%$$ -for the same meaning as -$codei% - CondExpGt(%flag%, %Type%(0), %if_true%, %if_false%) -%$$ -Use of $code CondExp$$ is deprecated, but continues to be supported. - -$head Operation Sequence$$ -This is an AD of $icode Base$$ -$cref/atomic operation/glossary/Operation/Atomic/$$ -and hence is part of the current -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - - -$head Example$$ - -$head Test$$ -$children% - example/cond_exp.cpp -%$$ -The file -$cref cond_exp.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$head Atan2$$ -The following implementation of the -AD $cref atan2$$ function is a more complex -example of using conditional expressions: -$code -$verbatim%cppad/local/atan2.hpp%0%BEGIN CondExp%// END CondExp%$$ -$$ - - -$end -------------------------------------------------------------------------------- -*/ -// BEGIN CppAD namespace -namespace CppAD { - -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -AD CondExpOp( - enum CompareOp cop , - const AD &left , - const AD &right , - const AD &if_true , - const AD &if_false ) -{ - AD returnValue; - CPPAD_ASSERT_UNKNOWN( Parameter(returnValue) ); - - // check first case where do not need to tape - if( IdenticalPar(left) & IdenticalPar(right) ) - { switch( cop ) - { - case CompareLt: - if( left.value_ < right.value_ ) - returnValue = if_true; - else returnValue = if_false; - break; - - case CompareLe: - if( left.value_ <= right.value_ ) - returnValue = if_true; - else returnValue = if_false; - break; - - case CompareEq: - if( left.value_ == right.value_ ) - returnValue = if_true; - else returnValue = if_false; - break; - - case CompareGe: - if( left.value_ >= right.value_ ) - returnValue = if_true; - else returnValue = if_false; - break; - - case CompareGt: - if( left.value_ > right.value_ ) - returnValue = if_true; - else returnValue = if_false; - break; - - default: - CPPAD_ASSERT_UNKNOWN(0); - returnValue = if_true; - } - return returnValue; - } - - // must use CondExp incase Base is an AD type and recording - returnValue.value_ = CondExpOp(cop, - left.value_, right.value_, if_true.value_, if_false.value_); - - ADTape *tape = CPPAD_NULL; - if( Variable(left) ) - tape = left.tape_this(); - if( Variable(right) ) - tape = right.tape_this(); - if( Variable(if_true) ) - tape = if_true.tape_this(); - if( Variable(if_false) ) - tape = if_false.tape_this(); - - // add this operation to the tape - if( tape != CPPAD_NULL ) - tape->RecordCondExp(cop, - returnValue, left, right, if_true, if_false); - - return returnValue; -} - -// --- RecordCondExp(cop, returnValue, left, right, if_true, if_false) ----- - -/// All these operations are done in \c Rec_, so we should move this -/// routine to recorder. -template -void ADTape::RecordCondExp( - enum CompareOp cop , - AD &returnValue , - const AD &left , - const AD &right , - const AD &if_true , - const AD &if_false ) -{ size_t ind0, ind1, ind2, ind3, ind4, ind5; - size_t returnValue_taddr; - - // taddr_ of this variable - CPPAD_ASSERT_UNKNOWN( NumRes(CExpOp) == 1 ); - returnValue_taddr = Rec_.PutOp(CExpOp); - - // ind[0] = cop - ind0 = addr_t( cop ); - - // ind[1] = base 2 representaion of the value - // [Var(left), Var(right), Var(if_true), Var(if_false)] - ind1 = 0; - - // Make sure returnValue is in the list of variables and set its taddr - if( Parameter(returnValue) ) - returnValue.make_variable(id_, returnValue_taddr ); - else returnValue.taddr_ = returnValue_taddr; - - // ind[2] = left address - if( Parameter(left) ) - ind2 = Rec_.PutPar(left.value_); - else - { ind1 += 1; - ind2 = left.taddr_; - } - - // ind[3] = right address - if( Parameter(right) ) - ind3 = Rec_.PutPar(right.value_); - else - { ind1 += 2; - ind3 = right.taddr_; - } - - // ind[4] = if_true address - if( Parameter(if_true) ) - ind4 = Rec_.PutPar(if_true.value_); - else - { ind1 += 4; - ind4 = if_true.taddr_; - } - - // ind[5] = if_false address - if( Parameter(if_false) ) - ind5 = Rec_.PutPar(if_false.value_); - else - { ind1 += 8; - ind5 = if_false.taddr_; - } - - CPPAD_ASSERT_UNKNOWN( NumArg(CExpOp) == 6 ); - CPPAD_ASSERT_UNKNOWN( ind1 > 0 ); - Rec_.PutArg(ind0, ind1, ind2, ind3, ind4, ind5); - - // check that returnValue is a dependent variable - CPPAD_ASSERT_UNKNOWN( Variable(returnValue) ); -} - -// ------------ CondExpOp(left, right, if_true, if_false) ---------------- - -# define CPPAD_COND_EXP(Name) \ - template \ - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION \ - AD CondExp##Name( \ - const AD &left , \ - const AD &right , \ - const AD &if_true , \ - const AD &if_false ) \ - { \ - return CondExpOp(Compare##Name, \ - left, right, if_true, if_false); \ - } - -// AD -CPPAD_COND_EXP(Lt) -CPPAD_COND_EXP(Le) -CPPAD_COND_EXP(Eq) -CPPAD_COND_EXP(Ge) -CPPAD_COND_EXP(Gt) -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -AD CondExp( - const AD &flag , - const AD &if_true , - const AD &if_false ) -{ - return CondExpOp(CompareGt, flag, AD(0), if_true, if_false); -} - -# undef CPPAD_COND_EXP -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/cond_op.hpp b/ct_core/include/ct/external/cppad/local/cond_op.hpp deleted file mode 100644 index df7a83620..000000000 --- a/ct_core/include/ct/external/cppad/local/cond_op.hpp +++ /dev/null @@ -1,1313 +0,0 @@ -// $Id: cond_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_COND_OP_HPP -# define CPPAD_COND_OP_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file cond_op.hpp -Forward, reverse, and sparse operations for conditional expressions. -*/ - -/*! -Shared documentation for conditional expressions (not called). - - -The C++ source code coresponding to this operation is -\verbatim - z = CondExpRel(y_0, y_1, y_2, y_3) -\endverbatim -where Rel is one of the following: Lt, Le, Eq, Ge, Gt. - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param i_z -is the AD variable index corresponding to the variable z. - -\param arg -\n -\a arg[0] -is static cast to size_t from the enum type -\verbatim - enum CompareOp { - CompareLt, - CompareLe, - CompareEq, - CompareGe, - CompareGt, - CompareNe - } -\endverbatim -for this operation. -Note that arg[0] cannot be equal to CompareNe. -\n -\n -\a arg[1] & 1 -\n -If this is zero, y_0 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 2 -\n -If this is zero, y_1 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 4 -\n -If this is zero, y_2 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 8 -\n -If this is zero, y_3 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[2 + j ] for j = 0, 1, 2, 3 -\n -is the index corresponding to y_j. - -\param num_par -is the total number of values in the vector \a parameter. - -\param parameter -For j = 0, 1, 2, 3, -if y_j is a parameter, \a parameter [ arg[2 + j] ] is its value. - -\param cap_order -number of columns in the matrix containing the Taylor coefficients. - -\par Checked Assertions -\li NumArg(CExpOp) == 6 -\li NumRes(CExpOp) == 1 -\li arg[0] < static_cast ( CompareNe ) -\li arg[1] != 0; i.e., not all of y_0, y_1, y_2, y_3 are parameters. -\li For j = 0, 1, 2, 3 if y_j is a parameter, arg[2+j] < num_par. - -*/ -template -inline void conditional_exp_op( - size_t i_z , - const addr_t* arg , - size_t num_par , - const Base* parameter , - size_t cap_order ) -{ // This routine is only for documentation, it should never be used - CPPAD_ASSERT_UNKNOWN( false ); -} - -/*! -Shared documentation for conditional expression sparse operations (not called). - - -The C++ source code coresponding to this operation is -\verbatim - z = CondExpRel(y_0, y_1, y_2, y_3) -\endverbatim -where Rel is one of the following: Lt, Le, Eq, Ge, Gt. - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param i_z -is the AD variable index corresponding to the variable z. - -\param arg -\n -\a arg[0] -is static cast to size_t from the enum type -\verbatim - enum CompareOp { - CompareLt, - CompareLe, - CompareEq, - CompareGe, - CompareGt, - CompareNe - } -\endverbatim -for this operation. -Note that arg[0] cannot be equal to CompareNe. -\n -\n -\a arg[1] & 1 -\n -If this is zero, y_0 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 2 -\n -If this is zero, y_1 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 4 -\n -If this is zero, y_2 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 8 -\n -If this is zero, y_3 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[2 + j ] for j = 0, 1, 2, 3 -\n -is the index corresponding to y_j. - -\param num_par -is the total number of values in the vector \a parameter. - -\par Checked Assertions -\li NumArg(CExpOp) == 6 -\li NumRes(CExpOp) == 1 -\li arg[0] < static_cast ( CompareNe ) -\li arg[1] != 0; i.e., not all of y_0, y_1, y_2, y_3 are parameters. -\li For j = 0, 1, 2, 3 if y_j is a parameter, arg[2+j] < num_par. - -*/ -template -inline void sparse_conditional_exp_op( - size_t i_z , - const addr_t* arg , - size_t num_par ) -{ // This routine is only for documentation, it should never be used - CPPAD_ASSERT_UNKNOWN( false ); -} - -/*! -Compute forward mode Taylor coefficients for op = CExpOp. - - -The C++ source code coresponding to this operation is -\verbatim - z = CondExpRel(y_0, y_1, y_2, y_3) -\endverbatim -where Rel is one of the following: Lt, Le, Eq, Ge, Gt. - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param i_z -is the AD variable index corresponding to the variable z. - -\param arg -\n -\a arg[0] -is static cast to size_t from the enum type -\verbatim - enum CompareOp { - CompareLt, - CompareLe, - CompareEq, - CompareGe, - CompareGt, - CompareNe - } -\endverbatim -for this operation. -Note that arg[0] cannot be equal to CompareNe. -\n -\n -\a arg[1] & 1 -\n -If this is zero, y_0 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 2 -\n -If this is zero, y_1 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 4 -\n -If this is zero, y_2 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 8 -\n -If this is zero, y_3 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[2 + j ] for j = 0, 1, 2, 3 -\n -is the index corresponding to y_j. - -\param num_par -is the total number of values in the vector \a parameter. - -\param parameter -For j = 0, 1, 2, 3, -if y_j is a parameter, \a parameter [ arg[2 + j] ] is its value. - -\param cap_order -number of columns in the matrix containing the Taylor coefficients. - -\par Checked Assertions -\li NumArg(CExpOp) == 6 -\li NumRes(CExpOp) == 1 -\li arg[0] < static_cast ( CompareNe ) -\li arg[1] != 0; i.e., not all of y_0, y_1, y_2, y_3 are parameters. -\li For j = 0, 1, 2, 3 if y_j is a parameter, arg[2+j] < num_par. - - -\param p -is the lowest order of the Taylor coefficient of z that we are computing. - -\param q -is the highest order of the Taylor coefficient of z that we are computing. - -\param taylor -\b Input: -For j = 0, 1, 2, 3 and k = 0 , ... , q, -if y_j is a variable then -taylor [ arg[2+j] * cap_order + k ] -is the k-th order Taylor coefficient corresponding to y_j. -\n -\b Input: taylor [ i_z * cap_order + k ] -for k = 0 , ... , p-1, -is the k-th order Taylor coefficient corresponding to z. -\n -\b Output: taylor [ i_z * cap_order + k ] -for k = p , ... , q, -is the k-th order Taylor coefficient corresponding to z. - -*/ -template -inline void forward_cond_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - size_t num_par , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ Base y_0, y_1, y_2, y_3; - Base zero(0); - Base* z = taylor + i_z * cap_order; - - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < static_cast (CompareNe) ); - CPPAD_ASSERT_UNKNOWN( NumArg(CExpOp) == 6 ); - CPPAD_ASSERT_UNKNOWN( NumRes(CExpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( arg[1] != 0 ); - - if( arg[1] & 1 ) - { - y_0 = taylor[ arg[2] * cap_order + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < num_par ); - y_0 = parameter[ arg[2] ]; - } - if( arg[1] & 2 ) - { - y_1 = taylor[ arg[3] * cap_order + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[3]) < num_par ); - y_1 = parameter[ arg[3] ]; - } - if( p == 0 ) - { if( arg[1] & 4 ) - { - y_2 = taylor[ arg[4] * cap_order + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[4]) < num_par ); - y_2 = parameter[ arg[4] ]; - } - if( arg[1] & 8 ) - { - y_3 = taylor[ arg[5] * cap_order + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[5]) < num_par ); - y_3 = parameter[ arg[5] ]; - } - z[0] = CondExpOp( - CompareOp( arg[0] ), - y_0, - y_1, - y_2, - y_3 - ); - p++; - } - for(size_t d = p; d <= q; d++) - { if( arg[1] & 4 ) - { - y_2 = taylor[ arg[4] * cap_order + d]; - } - else y_2 = zero; - if( arg[1] & 8 ) - { - y_3 = taylor[ arg[5] * cap_order + d]; - } - else y_3 = zero; - z[d] = CondExpOp( - CompareOp( arg[0] ), - y_0, - y_1, - y_2, - y_3 - ); - } - return; -} - -/*! -Multiple directions forward mode Taylor coefficients for op = CExpOp. - - -The C++ source code coresponding to this operation is -\verbatim - z = CondExpRel(y_0, y_1, y_2, y_3) -\endverbatim -where Rel is one of the following: Lt, Le, Eq, Ge, Gt. - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param i_z -is the AD variable index corresponding to the variable z. - -\param arg -\n -\a arg[0] -is static cast to size_t from the enum type -\verbatim - enum CompareOp { - CompareLt, - CompareLe, - CompareEq, - CompareGe, - CompareGt, - CompareNe - } -\endverbatim -for this operation. -Note that arg[0] cannot be equal to CompareNe. -\n -\n -\a arg[1] & 1 -\n -If this is zero, y_0 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 2 -\n -If this is zero, y_1 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 4 -\n -If this is zero, y_2 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 8 -\n -If this is zero, y_3 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[2 + j ] for j = 0, 1, 2, 3 -\n -is the index corresponding to y_j. - -\param num_par -is the total number of values in the vector \a parameter. - -\param parameter -For j = 0, 1, 2, 3, -if y_j is a parameter, \a parameter [ arg[2 + j] ] is its value. - -\param cap_order -number of columns in the matrix containing the Taylor coefficients. - -\par Checked Assertions -\li NumArg(CExpOp) == 6 -\li NumRes(CExpOp) == 1 -\li arg[0] < static_cast ( CompareNe ) -\li arg[1] != 0; i.e., not all of y_0, y_1, y_2, y_3 are parameters. -\li For j = 0, 1, 2, 3 if y_j is a parameter, arg[2+j] < num_par. - - -\param q -is order of the Taylor coefficient of z that we are computing. - -\param r -is the number of Taylor coefficient directions that we are computing. - -\par tpv -We use the notation -tpv = (cap_order-1) * r + 1 -which is the number of Taylor coefficients per variable - -\param taylor -\b Input: -For j = 0, 1, 2, 3, k = 1, ..., q, -if y_j is a variable then -taylor [ arg[2+j] * tpv + 0 ] -is the zero order Taylor coefficient corresponding to y_j and -taylor [ arg[2+j] * tpv + (k-1)*r+1+ell is its -k-th order Taylor coefficient in the ell-th direction. -\n -\b Input: -For j = 0, 1, 2, 3, k = 1, ..., q-1, -taylor [ i_z * tpv + 0 ] -is the zero order Taylor coefficient corresponding to z and -taylor [ i_z * tpv + (k-1)*r+1+ell is its -k-th order Taylor coefficient in the ell-th direction. -\n -\b Output: taylor [ i_z * tpv + (q-1)*r+1+ell ] -is the q-th order Taylor coefficient corresponding to z -in the ell-th direction. -*/ -template -inline void forward_cond_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - size_t num_par , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ Base y_0, y_1, y_2, y_3; - Base zero(0); - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* z = taylor + i_z * num_taylor_per_var; - - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < static_cast (CompareNe) ); - CPPAD_ASSERT_UNKNOWN( NumArg(CExpOp) == 6 ); - CPPAD_ASSERT_UNKNOWN( NumRes(CExpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( arg[1] != 0 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - if( arg[1] & 1 ) - { - y_0 = taylor[ arg[2] * num_taylor_per_var + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < num_par ); - y_0 = parameter[ arg[2] ]; - } - if( arg[1] & 2 ) - { - y_1 = taylor[ arg[3] * num_taylor_per_var + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[3]) < num_par ); - y_1 = parameter[ arg[3] ]; - } - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - { if( arg[1] & 4 ) - { - y_2 = taylor[ arg[4] * num_taylor_per_var + m + ell]; - } - else y_2 = zero; - if( arg[1] & 8 ) - { - y_3 = taylor[ arg[5] * num_taylor_per_var + m + ell]; - } - else y_3 = zero; - z[m+ell] = CondExpOp( - CompareOp( arg[0] ), - y_0, - y_1, - y_2, - y_3 - ); - } - return; -} - -/*! -Compute zero order forward mode Taylor coefficients for op = CExpOp. - - -The C++ source code coresponding to this operation is -\verbatim - z = CondExpRel(y_0, y_1, y_2, y_3) -\endverbatim -where Rel is one of the following: Lt, Le, Eq, Ge, Gt. - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param i_z -is the AD variable index corresponding to the variable z. - -\param arg -\n -\a arg[0] -is static cast to size_t from the enum type -\verbatim - enum CompareOp { - CompareLt, - CompareLe, - CompareEq, - CompareGe, - CompareGt, - CompareNe - } -\endverbatim -for this operation. -Note that arg[0] cannot be equal to CompareNe. -\n -\n -\a arg[1] & 1 -\n -If this is zero, y_0 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 2 -\n -If this is zero, y_1 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 4 -\n -If this is zero, y_2 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 8 -\n -If this is zero, y_3 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[2 + j ] for j = 0, 1, 2, 3 -\n -is the index corresponding to y_j. - -\param num_par -is the total number of values in the vector \a parameter. - -\param parameter -For j = 0, 1, 2, 3, -if y_j is a parameter, \a parameter [ arg[2 + j] ] is its value. - -\param cap_order -number of columns in the matrix containing the Taylor coefficients. - -\par Checked Assertions -\li NumArg(CExpOp) == 6 -\li NumRes(CExpOp) == 1 -\li arg[0] < static_cast ( CompareNe ) -\li arg[1] != 0; i.e., not all of y_0, y_1, y_2, y_3 are parameters. -\li For j = 0, 1, 2, 3 if y_j is a parameter, arg[2+j] < num_par. - - -\param taylor -\b Input: -For j = 0, 1, 2, 3, -if y_j is a variable then -\a taylor [ \a arg[2+j] * cap_order + 0 ] -is the zero order Taylor coefficient corresponding to y_j. -\n -\b Output: \a taylor [ \a i_z * \a cap_order + 0 ] -is the zero order Taylor coefficient corresponding to z. -*/ -template -inline void forward_cond_op_0( - size_t i_z , - const addr_t* arg , - size_t num_par , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ Base y_0, y_1, y_2, y_3; - Base* z; - - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < static_cast (CompareNe) ); - CPPAD_ASSERT_UNKNOWN( NumArg(CExpOp) == 6 ); - CPPAD_ASSERT_UNKNOWN( NumRes(CExpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( arg[1] != 0 ); - - if( arg[1] & 1 ) - { - y_0 = taylor[ arg[2] * cap_order + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < num_par ); - y_0 = parameter[ arg[2] ]; - } - if( arg[1] & 2 ) - { - y_1 = taylor[ arg[3] * cap_order + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[3]) < num_par ); - y_1 = parameter[ arg[3] ]; - } - if( arg[1] & 4 ) - { - y_2 = taylor[ arg[4] * cap_order + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[4]) < num_par ); - y_2 = parameter[ arg[4] ]; - } - if( arg[1] & 8 ) - { - y_3 = taylor[ arg[5] * cap_order + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[5]) < num_par ); - y_3 = parameter[ arg[5] ]; - } - z = taylor + i_z * cap_order; - z[0] = CondExpOp( - CompareOp( arg[0] ), - y_0, - y_1, - y_2, - y_3 - ); - return; -} - -/*! -Compute reverse mode Taylor coefficients for op = CExpOp. - -This routine is given the partial derivatives of a function -G( z , y , x , w , ... ) -and it uses them to compute the partial derivatives of -\verbatim - H( y , x , w , u , ... ) = G[ z(y) , y , x , w , u , ... ] -\endverbatim -where y above represents y_0, y_1, y_2, y_3. - - -The C++ source code coresponding to this operation is -\verbatim - z = CondExpRel(y_0, y_1, y_2, y_3) -\endverbatim -where Rel is one of the following: Lt, Le, Eq, Ge, Gt. - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param i_z -is the AD variable index corresponding to the variable z. - -\param arg -\n -\a arg[0] -is static cast to size_t from the enum type -\verbatim - enum CompareOp { - CompareLt, - CompareLe, - CompareEq, - CompareGe, - CompareGt, - CompareNe - } -\endverbatim -for this operation. -Note that arg[0] cannot be equal to CompareNe. -\n -\n -\a arg[1] & 1 -\n -If this is zero, y_0 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 2 -\n -If this is zero, y_1 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 4 -\n -If this is zero, y_2 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 8 -\n -If this is zero, y_3 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[2 + j ] for j = 0, 1, 2, 3 -\n -is the index corresponding to y_j. - -\param num_par -is the total number of values in the vector \a parameter. - -\param parameter -For j = 0, 1, 2, 3, -if y_j is a parameter, \a parameter [ arg[2 + j] ] is its value. - -\param cap_order -number of columns in the matrix containing the Taylor coefficients. - -\par Checked Assertions -\li NumArg(CExpOp) == 6 -\li NumRes(CExpOp) == 1 -\li arg[0] < static_cast ( CompareNe ) -\li arg[1] != 0; i.e., not all of y_0, y_1, y_2, y_3 are parameters. -\li For j = 0, 1, 2, 3 if y_j is a parameter, arg[2+j] < num_par. - - -\param d -is the order of the Taylor coefficient of z that we are computing. - -\param taylor -\b Input: -For j = 0, 1, 2, 3 and k = 0 , ... , \a d, -if y_j is a variable then -\a taylor [ \a arg[2+j] * cap_order + k ] -is the k-th order Taylor coefficient corresponding to y_j. -\n -\a taylor [ \a i_z * \a cap_order + k ] -for k = 0 , ... , \a d -is the k-th order Taylor coefficient corresponding to z. - -\param nc_partial -number of columns in the matrix containing the Taylor coefficients. - -\param partial -\b Input: -For j = 0, 1, 2, 3 and k = 0 , ... , \a d, -if y_j is a variable then -\a partial [ \a arg[2+j] * nc_partial + k ] -is the partial derivative of G( z , y , x , w , u , ... ) -with respect to the k-th order Taylor coefficient corresponding to y_j. -\n -\b Input: \a partial [ \a i_z * \a cap_order + k ] -for k = 0 , ... , \a d -is the partial derivative of G( z , y , x , w , u , ... ) -with respect to the k-th order Taylor coefficient corresponding to z. -\n -\b Output: -For j = 0, 1, 2, 3 and k = 0 , ... , \a d, -if y_j is a variable then -\a partial [ \a arg[2+j] * nc_partial + k ] -is the partial derivative of H( y , x , w , u , ... ) -with respect to the k-th order Taylor coefficient corresponding to y_j. - -*/ -template -inline void reverse_cond_op( - size_t d , - size_t i_z , - const addr_t* arg , - size_t num_par , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ Base y_0, y_1; - Base zero(0); - Base* pz; - Base* py_2; - Base* py_3; - - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < static_cast (CompareNe) ); - CPPAD_ASSERT_UNKNOWN( NumArg(CExpOp) == 6 ); - CPPAD_ASSERT_UNKNOWN( NumRes(CExpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( arg[1] != 0 ); - - pz = partial + i_z * nc_partial + 0; - if( arg[1] & 1 ) - { - y_0 = taylor[ arg[2] * cap_order + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < num_par ); - y_0 = parameter[ arg[2] ]; - } - if( arg[1] & 2 ) - { - y_1 = taylor[ arg[3] * cap_order + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[3]) < num_par ); - y_1 = parameter[ arg[3] ]; - } - if( arg[1] & 4 ) - { - py_2 = partial + arg[4] * nc_partial; - size_t j = d + 1; - while(j--) - { py_2[j] += CondExpOp( - CompareOp( arg[0] ), - y_0, - y_1, - pz[j], - zero - ); - } - } - if( arg[1] & 8 ) - { - py_3 = partial + arg[5] * nc_partial; - size_t j = d + 1; - while(j--) - { py_3[j] += CondExpOp( - CompareOp( arg[0] ), - y_0, - y_1, - zero, - pz[j] - ); - } - } - return; -} - -/*! -Compute forward Jacobian sparsity patterns for op = CExpOp. - - -The C++ source code coresponding to this operation is -\verbatim - z = CondExpRel(y_0, y_1, y_2, y_3) -\endverbatim -where Rel is one of the following: Lt, Le, Eq, Ge, Gt. - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param i_z -is the AD variable index corresponding to the variable z. - -\param arg -\n -\a arg[0] -is static cast to size_t from the enum type -\verbatim - enum CompareOp { - CompareLt, - CompareLe, - CompareEq, - CompareGe, - CompareGt, - CompareNe - } -\endverbatim -for this operation. -Note that arg[0] cannot be equal to CompareNe. -\n -\n -\a arg[1] & 1 -\n -If this is zero, y_0 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 2 -\n -If this is zero, y_1 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 4 -\n -If this is zero, y_2 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 8 -\n -If this is zero, y_3 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[2 + j ] for j = 0, 1, 2, 3 -\n -is the index corresponding to y_j. - -\param num_par -is the total number of values in the vector \a parameter. - -\par Checked Assertions -\li NumArg(CExpOp) == 6 -\li NumRes(CExpOp) == 1 -\li arg[0] < static_cast ( CompareNe ) -\li arg[1] != 0; i.e., not all of y_0, y_1, y_2, y_3 are parameters. -\li For j = 0, 1, 2, 3 if y_j is a parameter, arg[2+j] < num_par. - - -\param dependency -Are the derivatives with respect to left and right of the expression below -considered to be non-zero: -\code - CondExpRel(left, right, if_true, if_false) -\endcode -This is used by the optimizer to obtain the correct dependency relations. - -\param sparsity -\b Input: -if y_2 is a variable, the set with index t is -the sparsity pattern corresponding to y_2. -This identifies which of the independent variables the variable y_2 -depends on. -\n -\b Input: -if y_3 is a variable, the set with index t is -the sparsity pattern corresponding to y_3. -This identifies which of the independent variables the variable y_3 -depends on. -\n -\b Output: -The set with index T is -the sparsity pattern corresponding to z. -This identifies which of the independent variables the variable z -depends on. -*/ -template -inline void forward_sparse_jacobian_cond_op( - bool dependency , - size_t i_z , - const addr_t* arg , - size_t num_par , - Vector_set& sparsity ) -{ - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < static_cast (CompareNe) ); - CPPAD_ASSERT_UNKNOWN( NumArg(CExpOp) == 6 ); - CPPAD_ASSERT_UNKNOWN( NumRes(CExpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( arg[1] != 0 ); -# ifndef NDEBUG - size_t k = 1; - for( size_t j = 0; j < 4; j++) - { if( ! ( arg[1] & k ) ) - CPPAD_ASSERT_UNKNOWN( size_t(arg[2+j]) < num_par ); - k *= 2; - } -# endif - sparsity.clear(i_z); - if( dependency ) - { if( arg[1] & 1 ) - sparsity.binary_union(i_z, i_z, arg[2], sparsity); - if( arg[1] & 2 ) - sparsity.binary_union(i_z, i_z, arg[3], sparsity); - } - if( arg[1] & 4 ) - sparsity.binary_union(i_z, i_z, arg[4], sparsity); - if( arg[1] & 8 ) - sparsity.binary_union(i_z, i_z, arg[5], sparsity); - return; -} - -/*! -Compute reverse Jacobian sparsity patterns for op = CExpOp. - -This routine is given the sparsity patterns -for a function G(z, y, x, ... ) -and it uses them to compute the sparsity patterns for -\verbatim - H( y, x, w , u , ... ) = G[ z(x,y) , y , x , w , u , ... ] -\endverbatim -where y represents the combination of y_0, y_1, y_2, and y_3. - - -The C++ source code coresponding to this operation is -\verbatim - z = CondExpRel(y_0, y_1, y_2, y_3) -\endverbatim -where Rel is one of the following: Lt, Le, Eq, Ge, Gt. - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param i_z -is the AD variable index corresponding to the variable z. - -\param arg -\n -\a arg[0] -is static cast to size_t from the enum type -\verbatim - enum CompareOp { - CompareLt, - CompareLe, - CompareEq, - CompareGe, - CompareGt, - CompareNe - } -\endverbatim -for this operation. -Note that arg[0] cannot be equal to CompareNe. -\n -\n -\a arg[1] & 1 -\n -If this is zero, y_0 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 2 -\n -If this is zero, y_1 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 4 -\n -If this is zero, y_2 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 8 -\n -If this is zero, y_3 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[2 + j ] for j = 0, 1, 2, 3 -\n -is the index corresponding to y_j. - -\param num_par -is the total number of values in the vector \a parameter. - -\par Checked Assertions -\li NumArg(CExpOp) == 6 -\li NumRes(CExpOp) == 1 -\li arg[0] < static_cast ( CompareNe ) -\li arg[1] != 0; i.e., not all of y_0, y_1, y_2, y_3 are parameters. -\li For j = 0, 1, 2, 3 if y_j is a parameter, arg[2+j] < num_par. - - -\param dependency -Are the derivatives with respect to left and right of the expression below -considered to be non-zero: -\code - CondExpRel(left, right, if_true, if_false) -\endcode -This is used by the optimizer to obtain the correct dependency relations. - - -\param sparsity -if y_2 is a variable, the set with index t is -the sparsity pattern corresponding to y_2. -This identifies which of the dependent variables depend on the variable y_2. -On input, this pattern corresponds to the function G. -On ouput, it corresponds to the function H. -\n -\n -if y_3 is a variable, the set with index t is -the sparsity pattern corresponding to y_3. -This identifies which of the dependent variables depeond on the variable y_3. -On input, this pattern corresponds to the function G. -On ouput, it corresponds to the function H. -\n -\b Output: -The set with index T is -the sparsity pattern corresponding to z. -This identifies which of the dependent variables depend on the variable z. -On input and output, this pattern corresponds to the function G. -*/ -template -inline void reverse_sparse_jacobian_cond_op( - bool dependency , - size_t i_z , - const addr_t* arg , - size_t num_par , - Vector_set& sparsity ) -{ - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < static_cast (CompareNe) ); - CPPAD_ASSERT_UNKNOWN( NumArg(CExpOp) == 6 ); - CPPAD_ASSERT_UNKNOWN( NumRes(CExpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( arg[1] != 0 ); -# ifndef NDEBUG - size_t k = 1; - for( size_t j = 0; j < 4; j++) - { if( ! ( arg[1] & k ) ) - CPPAD_ASSERT_UNKNOWN( size_t(arg[2+j]) < num_par ); - k *= 2; - } -# endif - if( dependency ) - { if( arg[1] & 1 ) - sparsity.binary_union(arg[2], arg[2], i_z, sparsity); - if( arg[1] & 2 ) - sparsity.binary_union(arg[3], arg[3], i_z, sparsity); - } - // -------------------------------------------------------------------- - if( arg[1] & 4 ) - sparsity.binary_union(arg[4], arg[4], i_z, sparsity); - if( arg[1] & 8 ) - sparsity.binary_union(arg[5], arg[5], i_z, sparsity); - return; -} - -/*! -Compute reverse Hessian sparsity patterns for op = CExpOp. - -This routine is given the sparsity patterns -for a function G(z, y, x, ... ) -and it uses them to compute the sparsity patterns for -\verbatim - H( y, x, w , u , ... ) = G[ z(x,y) , y , x , w , u , ... ] -\endverbatim -where y represents the combination of y_0, y_1, y_2, and y_3. - - -The C++ source code coresponding to this operation is -\verbatim - z = CondExpRel(y_0, y_1, y_2, y_3) -\endverbatim -where Rel is one of the following: Lt, Le, Eq, Ge, Gt. - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param i_z -is the AD variable index corresponding to the variable z. - -\param arg -\n -\a arg[0] -is static cast to size_t from the enum type -\verbatim - enum CompareOp { - CompareLt, - CompareLe, - CompareEq, - CompareGe, - CompareGt, - CompareNe - } -\endverbatim -for this operation. -Note that arg[0] cannot be equal to CompareNe. -\n -\n -\a arg[1] & 1 -\n -If this is zero, y_0 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 2 -\n -If this is zero, y_1 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 4 -\n -If this is zero, y_2 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] & 8 -\n -If this is zero, y_3 is a parameter. Otherwise it is a variable. -\n -\n -\a arg[2 + j ] for j = 0, 1, 2, 3 -\n -is the index corresponding to y_j. - -\param num_par -is the total number of values in the vector \a parameter. - -\par Checked Assertions -\li NumArg(CExpOp) == 6 -\li NumRes(CExpOp) == 1 -\li arg[0] < static_cast ( CompareNe ) -\li arg[1] != 0; i.e., not all of y_0, y_1, y_2, y_3 are parameters. -\li For j = 0, 1, 2, 3 if y_j is a parameter, arg[2+j] < num_par. - - - -\param jac_reverse -\a jac_reverse[i_z] -is false (true) if the Jacobian of G with respect to z is always zero -(may be non-zero). -\n -\n -\a jac_reverse[ arg[4] ] -If y_2 is a variable, -\a jac_reverse[ arg[4] ] -is false (true) if the Jacobian with respect to y_2 is always zero -(may be non-zero). -On input, it corresponds to the function G, -and on output it corresponds to the function H. -\n -\n -\a jac_reverse[ arg[5] ] -If y_3 is a variable, -\a jac_reverse[ arg[5] ] -is false (true) if the Jacobian with respect to y_3 is always zero -(may be non-zero). -On input, it corresponds to the function G, -and on output it corresponds to the function H. - -\param hes_sparsity -The set with index \a i_z in \a hes_sparsity -is the Hessian sparsity pattern for the function G -where one of the partials is with respect to z. -\n -\n -If y_2 is a variable, -the set with index \a arg[4] in \a hes_sparsity -is the Hessian sparsity pattern -where one of the partials is with respect to y_2. -On input, this pattern corresponds to the function G. -On output, this pattern corresponds to the function H. -\n -\n -If y_3 is a variable, -the set with index \a arg[5] in \a hes_sparsity -is the Hessian sparsity pattern -where one of the partials is with respect to y_3. -On input, this pattern corresponds to the function G. -On output, this pattern corresponds to the function H. -*/ -template -inline void reverse_sparse_hessian_cond_op( - size_t i_z , - const addr_t* arg , - size_t num_par , - bool* jac_reverse , - Vector_set& hes_sparsity ) -{ - - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < static_cast (CompareNe) ); - CPPAD_ASSERT_UNKNOWN( NumArg(CExpOp) == 6 ); - CPPAD_ASSERT_UNKNOWN( NumRes(CExpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( arg[1] != 0 ); -# ifndef NDEBUG - size_t k = 1; - for( size_t j = 0; j < 4; j++) - { if( ! ( arg[1] & k ) ) - CPPAD_ASSERT_UNKNOWN( size_t(arg[2+j]) < num_par ); - k *= 2; - } -# endif - if( arg[1] & 4 ) - { - hes_sparsity.binary_union(arg[4], arg[4], i_z, hes_sparsity); - jac_reverse[ arg[4] ] |= jac_reverse[i_z]; - } - if( arg[1] & 8 ) - { - hes_sparsity.binary_union(arg[5], arg[5], i_z, hes_sparsity); - jac_reverse[ arg[5] ] |= jac_reverse[i_z]; - } - return; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/convert.hpp b/ct_core/include/ct/external/cppad/local/convert.hpp deleted file mode 100644 index 9c0d60533..000000000 --- a/ct_core/include/ct/external/cppad/local/convert.hpp +++ /dev/null @@ -1,52 +0,0 @@ -// $Id: convert.hpp 3769 2015-12-29 16:13:16Z bradbell $ -# ifndef CPPAD_CONVERT_HPP -# define CPPAD_CONVERT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Convert$$ -$spell -$$ - - -$section Conversion and I/O of AD Objects$$ -$mindex convert from$$ - -$children% - cppad/local/value.hpp% - cppad/local/integer.hpp% - cppad/local/ad_to_string.hpp% - cppad/local/ad_io.hpp% - cppad/local/print_for.hpp% - cppad/local/var2par.hpp -%$$ -$table -$rref Value$$ -$rref Integer$$ -$rref ad_output$$ -$rref PrintFor$$ -$rref Var2Par$$ -$tend - - -$end -*/ - -# include -# include -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/local/cos_op.hpp b/ct_core/include/ct/external/cppad/local/cos_op.hpp deleted file mode 100644 index 8e4310c1e..000000000 --- a/ct_core/include/ct/external/cppad/local/cos_op.hpp +++ /dev/null @@ -1,239 +0,0 @@ -// $Id: cos_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_COS_OP_HPP -# define CPPAD_COS_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file cos_op.hpp -Forward and reverse mode calculations for z = cos(x). -*/ - -/*! -Compute forward mode Taylor coefficient for result of op = CosOp. - -The C++ source code corresponding to this operation is -\verbatim - z = cos(x) -\endverbatim -The auxillary result is -\verbatim - y = sin(x) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op -*/ -template -inline void forward_cos_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(CosOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(CosOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* c = taylor + i_z * cap_order; - Base* s = c - cap_order; - - - // rest of this routine is identical for the following cases: - // forward_sin_op, forward_cos_op, forward_sinh_op, forward_cosh_op. - // (except that there is a sign difference for the hyperbolic case). - size_t k; - if( p == 0 ) - { s[0] = sin( x[0] ); - c[0] = cos( x[0] ); - p++; - } - for(size_t j = p; j <= q; j++) - { - s[j] = Base(0); - c[j] = Base(0); - for(k = 1; k <= j; k++) - { s[j] += Base(k) * x[k] * c[j-k]; - c[j] -= Base(k) * x[k] * s[j-k]; - } - s[j] /= Base(j); - c[j] /= Base(j); - } -} -/*! -Compute forward mode Taylor coefficient for result of op = CosOp. - -The C++ source code corresponding to this operation is -\verbatim - z = cos(x) -\endverbatim -The auxillary result is -\verbatim - y = sin(x) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op_dir -*/ -template -inline void forward_cos_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(CosOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(CosOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* c = taylor + i_z * num_taylor_per_var; - Base* s = c - num_taylor_per_var; - - - // rest of this routine is identical for the following cases: - // forward_sin_op, forward_cos_op, forward_sinh_op, forward_cosh_op - // (except that there is a sign difference for the hyperbolic case). - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - { s[m+ell] = Base(q) * x[m + ell] * c[0]; - c[m+ell] = - Base(q) * x[m + ell] * s[0]; - for(size_t k = 1; k < q; k++) - { s[m+ell] += Base(k) * x[(k-1)*r+1+ell] * c[(q-k-1)*r+1+ell]; - c[m+ell] -= Base(k) * x[(k-1)*r+1+ell] * s[(q-k-1)*r+1+ell]; - } - s[m+ell] /= Base(q); - c[m+ell] /= Base(q); - } -} - -/*! -Compute zero order forward mode Taylor coefficient for result of op = CosOp. - -The C++ source code corresponding to this operation is -\verbatim - z = cos(x) -\endverbatim -The auxillary result is -\verbatim - y = sin(x) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails forward_unary2_op_0 -*/ -template -inline void forward_cos_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(CosOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(CosOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* c = taylor + i_z * cap_order; // called z in documentation - Base* s = c - cap_order; // called y in documentation - - c[0] = cos( x[0] ); - s[0] = sin( x[0] ); -} -/*! -Compute reverse mode partial derivatives for result of op = CosOp. - -The C++ source code corresponding to this operation is -\verbatim - z = cos(x) -\endverbatim -The auxillary result is -\verbatim - y = sin(x) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails reverse_unary2_op -*/ - -template -inline void reverse_cos_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(CosOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(CosOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to first result - const Base* c = taylor + i_z * cap_order; // called z in doc - Base* pc = partial + i_z * nc_partial; - - // Taylor coefficients and partials corresponding to auxillary result - const Base* s = c - cap_order; // called y in documentation - Base* ps = pc - nc_partial; - - - // rest of this routine is identical for the following cases: - // reverse_sin_op, reverse_cos_op, reverse_sinh_op, reverse_cosh_op. - size_t j = d; - size_t k; - while(j) - { - ps[j] /= Base(j); - pc[j] /= Base(j); - for(k = 1; k <= j; k++) - { - px[k] += Base(k) * azmul(ps[j], c[j-k]); - px[k] -= Base(k) * azmul(pc[j], s[j-k]); - - ps[j-k] -= Base(k) * azmul(pc[j], x[k]); - pc[j-k] += Base(k) * azmul(ps[j], x[k]); - - } - --j; - } - px[0] += azmul(ps[0], c[0]); - px[0] -= azmul(pc[0], s[0]); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/cosh_op.hpp b/ct_core/include/ct/external/cppad/local/cosh_op.hpp deleted file mode 100644 index b37f34fcc..000000000 --- a/ct_core/include/ct/external/cppad/local/cosh_op.hpp +++ /dev/null @@ -1,239 +0,0 @@ -// $Id: cosh_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_COSH_OP_HPP -# define CPPAD_COSH_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file cosh_op.hpp -Forward and reverse mode calculations for z = cosh(x). -*/ - - -/*! -Compute forward mode Taylor coefficient for result of op = CoshOp. - -The C++ source code corresponding to this operation is -\verbatim - z = cosh(x) -\endverbatim -The auxillary result is -\verbatim - y = sinh(x) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op -*/ -template -inline void forward_cosh_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(CoshOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(CoshOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* c = taylor + i_z * cap_order; - Base* s = c - cap_order; - - // rest of this routine is identical for the following cases: - // forward_sin_op, forward_cos_op, forward_sinh_op, forward_cosh_op. - // (except that there is a sign difference for hyperbolic case). - size_t k; - if( p == 0 ) - { s[0] = sinh( x[0] ); - c[0] = cosh( x[0] ); - p++; - } - for(size_t j = p; j <= q; j++) - { - s[j] = Base(0); - c[j] = Base(0); - for(k = 1; k <= j; k++) - { s[j] += Base(k) * x[k] * c[j-k]; - c[j] += Base(k) * x[k] * s[j-k]; - } - s[j] /= Base(j); - c[j] /= Base(j); - } -} -/*! -Compute forward mode Taylor coefficient for result of op = CoshOp. - -The C++ source code corresponding to this operation is -\verbatim - z = cosh(x) -\endverbatim -The auxillary result is -\verbatim - y = sinh(x) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op_dir -*/ -template -inline void forward_cosh_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(CoshOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(CoshOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* s = taylor + i_z * num_taylor_per_var; - Base* c = s - num_taylor_per_var; - - - // rest of this routine is identical for the following cases: - // forward_sin_op, forward_cos_op, forward_sinh_op, forward_cosh_op - // (except that there is a sign difference for the hyperbolic case). - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - { s[m+ell] = Base(q) * x[m + ell] * c[0]; - c[m+ell] = Base(q) * x[m + ell] * s[0]; - for(size_t k = 1; k < q; k++) - { s[m+ell] += Base(k) * x[(k-1)*r+1+ell] * c[(q-k-1)*r+1+ell]; - c[m+ell] += Base(k) * x[(k-1)*r+1+ell] * s[(q-k-1)*r+1+ell]; - } - s[m+ell] /= Base(q); - c[m+ell] /= Base(q); - } -} - -/*! -Compute zero order forward mode Taylor coefficient for result of op = CoshOp. - -The C++ source code corresponding to this operation is -\verbatim - z = cosh(x) -\endverbatim -The auxillary result is -\verbatim - y = sinh(x) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails forward_unary2_op_0 -*/ -template -inline void forward_cosh_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(CoshOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(CoshOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* c = taylor + i_z * cap_order; // called z in documentation - Base* s = c - cap_order; // called y in documentation - - c[0] = cosh( x[0] ); - s[0] = sinh( x[0] ); -} -/*! -Compute reverse mode partial derivatives for result of op = CoshOp. - -The C++ source code corresponding to this operation is -\verbatim - z = cosh(x) -\endverbatim -The auxillary result is -\verbatim - y = sinh(x) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails reverse_unary2_op -*/ - -template -inline void reverse_cosh_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(CoshOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(CoshOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to first result - const Base* c = taylor + i_z * cap_order; // called z in doc - Base* pc = partial + i_z * nc_partial; - - // Taylor coefficients and partials corresponding to auxillary result - const Base* s = c - cap_order; // called y in documentation - Base* ps = pc - nc_partial; - - - // rest of this routine is identical for the following cases: - // reverse_sin_op, reverse_cos_op, reverse_sinh_op, reverse_cosh_op. - size_t j = d; - size_t k; - while(j) - { - ps[j] /= Base(j); - pc[j] /= Base(j); - for(k = 1; k <= j; k++) - { - px[k] += Base(k) * azmul(ps[j], c[j-k]); - px[k] += Base(k) * azmul(pc[j], s[j-k]); - - ps[j-k] += Base(k) * azmul(pc[j], x[k]); - pc[j-k] += Base(k) * azmul(ps[j], x[k]); - - } - --j; - } - px[0] += azmul(ps[0], c[0]); - px[0] += azmul(pc[0], s[0]); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/cppad_assert.hpp b/ct_core/include/ct/external/cppad/local/cppad_assert.hpp deleted file mode 100644 index ae1d62d1a..000000000 --- a/ct_core/include/ct/external/cppad/local/cppad_assert.hpp +++ /dev/null @@ -1,205 +0,0 @@ -// $Id: cppad_assert.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_CPPAD_ASSERT_HPP -# define CPPAD_CPPAD_ASSERT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/*! -\file cppad_assert.hpp -Define the CppAD error checking macros (all of which begin with CPPAD_ASSERT_) -*/ - -/* -------------------------------------------------------------------------------- -$begin cppad_assert$$ -$spell - CppAD - exp - const - bool -$$ - - -$section CppAD Assertions During Execution$$ -$mindex assert macro CPPAD_ASSERT_KNOWN CPPAD_ASSERT_UNKNOWN$$ - -$head Syntax$$ -$codei%CPPAD_ASSERT_KNOWN(%exp%, %msg%) -%$$ -$codei%CPPAD_ASSERT_UNKNOWN(%exp%)%$$ - - -$head Purpose$$ -These CppAD macros are used to detect and report errors. -They are documented here because they correspond to the C++ -source code that the error is reported at. - -$head NDEBUG$$ -If the preprocessor symbol -$cref/NDEBUG/Faq/Speed/NDEBUG/$$ is defined, -these macros do nothing; i.e., they are optimized out. - -$head Restriction$$ -The CppAD user should not uses these macros. -You can however write your own macros that do not begin with $code CPPAD$$ -and that call the $cref/CppAD error handler/ErrorHandler/$$. - -$head Known$$ -The $code CPPAD_ASSERT_KNOWN$$ macro is used to check for an error -with a known cause. -For example, many CppAD routines uses these macros -to make sure their arguments conform to their specifications. - -$head Unknown$$ -The $code CPPAD_ASSERT_UNKNOWN$$ macro is used to check that the -CppAD internal data structures conform as expected. -If this is not the case, CppAD does not know why the error has -occurred; for example, the user may have written past the end -of an allocated array. - -$head Exp$$ -The argument $icode exp$$ is a C++ source code expression -that results in a $code bool$$ value that should be true. -If it is false, an error has occurred. -This expression may be execute any number of times -(including zero times) so it must have not side effects. - -$head Msg$$ -The argument $icode msg$$ has prototype -$codei% - const char *%msg% -%$$ -and contains a $code '\0'$$ terminated character string. -This string is a description of the error -corresponding to $icode exp$$ being false. - -$head Error Handler$$ -These macros use the -$cref/CppAD error handler/ErrorHandler/$$ to report errors. -This error handler can be replaced by the user. - -$end ------------------------------------------------------------------------------- -*/ - -# include -# include -# include - -/*! -\def CPPAD_ASSERT_KNOWN(exp, msg) -Check that \a exp is true, if not print \a msg and terminate execution. - -The C++ expression \a exp is expected to be true. -If it is false, -the CppAD use has made an error that is described by \a msg. -If the preprocessor symbol \a NDEBUG is not defined, -and \a exp is false, -this macro will report the source code line number at -which this expected result occurred. -In addition, it will print the specified error message \a msg. -*/ -# ifdef NDEBUG -# define CPPAD_ASSERT_KNOWN(exp, msg) // do nothing -# else -# define CPPAD_ASSERT_KNOWN(exp, msg) \ -{ if( ! ( exp ) ) \ - CppAD::ErrorHandler::Call( \ - true , \ - __LINE__ , \ - __FILE__ , \ - #exp , \ - msg ); \ -} -# endif - -/*! -\def CPPAD_ASSERT_UNKNOWN(exp) -Check that \a exp is true, if not terminate execution. - -The C++ expression \a exp is expected to be true. -If it is false, -CppAD has detected an error but does not know the cause of the error. -If the preprocessor symbol \a NDEBUG is not defined, -and \a exp is false, -this macro will report the source code line number at -which this expected result occurred. -*/ -# ifdef NDEBUG -# define CPPAD_ASSERT_UNKNOWN(exp) // do nothing -# else -# define CPPAD_ASSERT_UNKNOWN(exp) \ -{ if( ! ( exp ) ) \ - CppAD::ErrorHandler::Call( \ - false , \ - __LINE__ , \ - __FILE__ , \ - #exp , \ - "" ); \ -} -# endif - -/*! -\def CPPAD_ASSERT_NARG_NRES(op, n_arg, n_res) -Check that operator \a op has the specified number of of arguments and results. - -If \a NDEBUG is not defined and either the number of arguments -or the number of results are not as expected, -execution is terminated and the source code line number is reported. -*/ -# define CPPAD_ASSERT_NARG_NRES(op, n_arg, n_res) \ - CPPAD_ASSERT_UNKNOWN( NumArg(op) == n_arg ) \ - CPPAD_ASSERT_UNKNOWN( NumRes(op) == n_res ) - -/*! -\def CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -Check that the first call to a routine is not during parallel execution mode. - -If \c NDEBUG is defined, this macro has no effect -(not even the definition of (\c assert_first_call). -Otherwise, the variable -\code - static bool assert_first_call -\endcode -is defined and if the first call is executed in parallel mode, -execution is terminated and the source code line number is reported. -*/ -# ifdef NDEBUG -# define CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# else -# define CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL \ - static bool assert_first_call = true; \ - if( assert_first_call ) \ - { CPPAD_ASSERT_KNOWN( \ - ! (CppAD::thread_alloc::in_parallel() ), \ - "In parallel mode and parallel_setup has not been called." \ - ); \ - assert_first_call = false; \ - } -# endif - -/*! -\def CPPAD_ASSERT_ARG_BEFORE_RESULT -Check that operator arguments come before result. - -If \c NDEBUG is defined, this macro has no effect, -otherwise it calls the function assert_arg_before_result. -*/ -# ifdef NDEBUG -# define CPPAD_ASSERT_ARG_BEFORE_RESULT(op, arg, result) -# else -# define CPPAD_ASSERT_ARG_BEFORE_RESULT(op, arg, result) \ - assert_arg_before_result(op, arg, result) - -# endif - -# endif diff --git a/ct_core/include/ct/external/cppad/local/cppad_colpack.hpp b/ct_core/include/ct/external/cppad/local/cppad_colpack.hpp deleted file mode 100644 index 3e5d9bba5..000000000 --- a/ct_core/include/ct/external/cppad/local/cppad_colpack.hpp +++ /dev/null @@ -1,104 +0,0 @@ -// $Id: cppad_colpack.hpp 3757 2015-11-30 12:03:07Z bradbell $ -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# ifndef CPPAD_CPPAD_COLPACK_HPP -# define CPPAD_CPPAD_COLPACK_HPP -# if CPPAD_HAS_COLPACK - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file cppad_colpack.hpp -External interface to Colpack routines used by cppad. -*/ -// --------------------------------------------------------------------------- -/*! -Link from CppAD to ColPack used for general sparse matrices. - -This CppAD library routine is necessary because -ColPack/ColPackHeaders.h has a -using namespace std at the global level. - -\param m [in] -is the number of rows in the sparse matrix - -\param n [in] -is the nubmer of columns in the sparse matrix. - -\param adolc_pattern [in] -This vector has size \c m, -adolc_pattern[i][0] is the number of non-zeros in row \c i. -For j = 1 , ... , adolc_sparsity[i], -adolc_pattern[i][j] is the column index (base zero) for the -non-zeros in row \c i. - -\param color [out] -is a vector with size \c m. -The input value of its elements does not matter. -Upon return, it is a coloring for the rows of the sparse matrix. -\n -\n -If for some \c i, color[i] == m, then -adolc_pattern[i][0] == 0. -Otherwise, color[i] < m. -\n -\n -Suppose two differen rows, i != r have the same color. -It follows that for all column indices \c j; -it is not the case that both -(i, j) and (r, j) appear in the sparsity pattern. -\n -\n -This routine tries to minimize, with respect to the choice of colors, -the number of colors. -*/ -extern void cppad_colpack_general( - CppAD::vector& color , - size_t m , - size_t n , - const CppAD::vector& adolc_pattern -); - -/*! -Link from CppAD to ColPack used for symmetric sparse matrices -(not yet used or tested). - -This CppAD library routine is necessary because -ColPack/ColPackHeaders.h has a -using namespace std at the global level. - -\param n [in] -is the nubmer of rows and columns in the symmetric sparse matrix. - -\param adolc_pattern [in] -This vector has size \c n, -adolc_pattern[i][0] is the number of non-zeros in row \c i. -For j = 1 , ... , adolc_sparsity[i], -adolc_pattern[i][j] is the column index (base zero) for the -non-zeros in row \c i. - -\param color [out] -The input value of its elements does not matter. -Upon return, it is a coloring for the rows of the sparse matrix. -The properties of this coloring have not yet been determined; see -Efficient Computation of Sparse Hessians Using Coloring -and Automatic Differentiation (pdf/ad/gebemedhin14.pdf) -*/ -extern void cppad_colpack_symmetric( - CppAD::vector& color , - size_t n , - const CppAD::vector& adolc_pattern -); - -} // END_CPPAD_NAMESPACE - -# endif -# endif - diff --git a/ct_core/include/ct/external/cppad/local/cskip_op.hpp b/ct_core/include/ct/external/cppad/local/cskip_op.hpp deleted file mode 100644 index e5f924bff..000000000 --- a/ct_core/include/ct/external/cppad/local/cskip_op.hpp +++ /dev/null @@ -1,199 +0,0 @@ -// $Id: cskip_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_CSKIP_OP_HPP -# define CPPAD_CSKIP_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file cskip_op.hpp -Zero order forward mode set which operations to skip. -*/ - -/*! -Zero order forward mode execution of op = CSkipOp. - -\par Parameters and Variables -The terms parameter and variable depend on if we are referring to its -AD or Base value. -We use Base parameter and Base variable to refer to the -correspond Base value. -We use AD parameter and AD variable to refer to the -correspond AD value. - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD and computations by this routine are done using type Base. - -\param i_z -variable index corresponding to the result of the previous operation. -This is used for error checking. To be specific, -the left and right operands for the CExpOp operation must have indexes -less than or equal this value. - -\param arg [in] -\n -\a arg[0] -is static cast to size_t from the enum type -\verbatim - enum CompareOp { - CompareLt, - CompareLe, - CompareEq, - CompareGe, - CompareGt, - CompareNe - } -\endverbatim -for this operation. -Note that arg[0] cannot be equal to CompareNe. -\n -\n -\a arg[1] & 1 -\n -If this is zero, left is an AD parameter. -Otherwise it is an AD variable. -\n -\n -\a arg[1] & 2 -\n -If this is zero, right is an AD parameter. -Otherwise it is an AD variable. -\n -\a arg[2] -is the index corresponding to left in comparision. -\n -\a arg[3] -is the index corresponding to right in comparision. -\n -\a arg[4] -is the number of operations to skip if the comparision result is true. -\n -\a arg[5] -is the number of operations to skip if the comparision result is false. -\n -arg[5+i] -for i = 1 , ... , arg[4] are the operations to skip if the -comparision result is true and both left and right are -identically Base parameters. -\n -arg[5+arg[4]+i] -for i = 1 , ... , arg[5] are the operations to skip if the -comparision result is false and both left and right are -identically Base parameters. - -\param num_par [in] -is the total number of values in the vector parameter. - -\param parameter [in] -If left is an AD parameter, -parameter [ arg[2] ] is its value. -If right is an AD parameter, -parameter [ arg[3] ] is its value. - -\param cap_order [in] -number of columns in the matrix containing the Taylor coefficients. - -\param taylor [in] -If left is an AD variable, -taylor [ arg[2] * cap_order + 0 ] -is the zeroth order Taylor coefficient corresponding to left. -If right is an AD variable, -taylor [ arg[3] * cap_order + 0 ] -is the zeroth order Taylor coefficient corresponding to right. - -\param cskip_op [in,out] -is vector specifying which operations are at this point are know to be -unecessary and can be skipped. -This is both an input and an output. -*/ -template -inline void forward_cskip_op_0( - size_t i_z , - const addr_t* arg , - size_t num_par , - const Base* parameter , - size_t cap_order , - Base* taylor , - bool* cskip_op ) -{ - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < size_t(CompareNe) ); - CPPAD_ASSERT_UNKNOWN( arg[1] != 0 ); - - Base left, right; - if( arg[1] & 1 ) - { // If varialbe arg[2] <= i_z, it has already been computed, - // but it will be skipped for higher orders. - left = taylor[ arg[2] * cap_order + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < num_par ); - left = parameter[ arg[2] ]; - } - if( arg[1] & 2 ) - { // If varialbe arg[3] <= i_z, it has already been computed, - // but it will be skipped for higher orders. - right = taylor[ arg[3] * cap_order + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[3]) < num_par ); - right = parameter[ arg[3] ]; - } - bool ok_to_skip = IdenticalPar(left) & IdenticalPar(right); - if( ! ok_to_skip ) - return; - - // initialize to avoid compiler warning - bool true_case = false; - Base diff = left - right; - switch( CompareOp( arg[0] ) ) - { - case CompareLt: - true_case = LessThanZero(diff); - break; - - case CompareLe: - true_case = LessThanOrZero(diff); - break; - - case CompareEq: - true_case = IdenticalZero(diff); - break; - - case CompareGe: - true_case = GreaterThanOrZero(diff); - break; - - case CompareGt: - true_case = GreaterThanZero(diff); - break; - - case CompareNe: - true_case = ! IdenticalZero(diff); - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } - if( true_case ) - { for(size_t i = 0; i < size_t(arg[4]); i++) - cskip_op[ arg[6+i] ] = true; - } - else - { for(size_t i = 0; i < size_t(arg[5]); i++) - cskip_op[ arg[6+arg[4]+i] ] = true; - } - return; -} -} // END_CPPAD_NAMESPACE -# endif - diff --git a/ct_core/include/ct/external/cppad/local/csum_op.hpp b/ct_core/include/ct/external/cppad/local/csum_op.hpp deleted file mode 100644 index 1746b5976..000000000 --- a/ct_core/include/ct/external/cppad/local/csum_op.hpp +++ /dev/null @@ -1,623 +0,0 @@ -// $Id: csum_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_CSUM_OP_HPP -# define CPPAD_CSUM_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file csum_op.hpp -Forward, reverse and sparsity calculations for cummulative summation. -*/ - -/*! -Compute forward mode Taylor coefficients for result of op = CsumOp. - -This operation is -\verbatim - z = s + x(1) + ... + x(m) - y(1) - ... - y(n). -\endverbatim - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param p -lowest order of the Taylor coefficient that we are computing. - -\param q -highest order of the Taylor coefficient that we are computing. - -\param i_z -variable index corresponding to the result for this operation; -i.e. the row index in \a taylor corresponding to z. - -\param arg -\a arg[0] -is the number of addition variables in this cummulative summation; i.e., -m. -\n -\a arg[1] -is the number of subtraction variables in this cummulative summation; i.e., -\c m. -\n -parameter[ arg[2] ] -is the parameter value \c s in this cummunative summation. -\n -arg[2+i] -for i = 1 , ... , m is the variable index of x(i). -\n -arg[2+arg[0]+i] -for i = 1 , ... , n is the variable index of y(i). - -\param num_par -is the number of parameters in \a parameter. - -\param parameter -is the parameter vector for this operation sequence. - -\param cap_order -number of colums in the matrix containing all the Taylor coefficients. - -\param taylor -\b Input: taylor [ arg[2+i] * cap_order + k ] -for i = 1 , ... , m -and k = 0 , ... , q -is the k-th order Taylor coefficient corresponding to x(i) -\n -\b Input: taylor [ arg[2+m+i] * cap_order + k ] -for i = 1 , ... , n -and k = 0 , ... , q -is the k-th order Taylor coefficient corresponding to y(i) -\n -\b Input: taylor [ i_z * cap_order + k ] -for k = 0 , ... , p, -is the k-th order Taylor coefficient corresponding to z. -\n -\b Output: taylor [ i_z * cap_order + k ] -for k = p , ... , q, -is the \a k-th order Taylor coefficient corresponding to z. -*/ -template -inline void forward_csum_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - size_t num_par , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ Base zero(0); - size_t i, j, k; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumRes(CSumOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < num_par ); - CPPAD_ASSERT_UNKNOWN( - arg[0] + arg[1] == arg[ arg[0] + arg[1] + 3 ] - ); - - // Taylor coefficients corresponding to result - Base* z = taylor + i_z * cap_order; - for(k = p; k <= q; k++) - z[k] = zero; - if( p == 0 ) - z[p] = parameter[ arg[2] ]; - Base* x; - i = arg[0]; - j = 2; - while(i--) - { CPPAD_ASSERT_UNKNOWN( size_t(arg[j+1]) < i_z ); - x = taylor + arg[++j] * cap_order; - for(k = p; k <= q; k++) - z[k] += x[k]; - } - i = arg[1]; - while(i--) - { CPPAD_ASSERT_UNKNOWN( size_t(arg[j+1]) < i_z ); - x = taylor + arg[++j] * cap_order; - for(k = p; k <= q; k++) - z[k] -= x[k]; - } -} - -/*! -Multiple direction forward mode Taylor coefficients for op = CsumOp. - -This operation is -\verbatim - z = s + x(1) + ... + x(m) - y(1) - ... - y(n). -\endverbatim - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD and computations by this routine are done using type -\a Base. - -\param q -order ot the Taylor coefficients that we are computing. - -\param r -number of directions for Taylor coefficients that we are computing. - -\param i_z -variable index corresponding to the result for this operation; -i.e. the row index in \a taylor corresponding to z. - -\param arg -\a arg[0] -is the number of addition variables in this cummulative summation; i.e., -m. -\n -\a arg[1] -is the number of subtraction variables in this cummulative summation; i.e., -\c m. -\n -parameter[ arg[2] ] -is the parameter value \c s in this cummunative summation. -\n -arg[2+i] -for i = 1 , ... , m is the variable index of x(i). -\n -arg[2+arg[0]+i] -for i = 1 , ... , n is the variable index of y(i). - -\param num_par -is the number of parameters in \a parameter. - -\param parameter -is the parameter vector for this operation sequence. - -\param cap_order -number of colums in the matrix containing all the Taylor coefficients. - -\param taylor -\b Input: taylor [ arg[2+i]*((cap_order-1)*r + 1) + 0 ] -for i = 1 , ... , m -is the 0-th order Taylor coefficient corresponding to x(i) and -taylor [ arg[2+i]*((cap_order-1)*r + 1) + (q-1)*r + ell + 1 ] -for i = 1 , ... , m, -ell = 0 , ... , r-1 -is the q-th order Taylor coefficient corresponding to x(i) -and direction ell. -\n -\b Input: taylor [ arg[2+m+i]*((cap_order-1)*r + 1) + 0 ] -for i = 1 , ... , n -is the 0-th order Taylor coefficient corresponding to y(i) and -taylor [ arg[2+m+i]*((cap_order-1)*r + 1) + (q-1)*r + ell + 1 ] -for i = 1 , ... , n, -ell = 0 , ... , r-1 -is the q-th order Taylor coefficient corresponding to y(i) -and direction ell. -\n -\b Output: taylor [ i_z*((cap_order-1)*r+1) + (q-1)*r + ell + 1 ] -is the \a q-th order Taylor coefficient corresponding to z -for direction ell = 0 , ... , r-1. -*/ -template -inline void forward_csum_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - size_t num_par , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ Base zero(0); - size_t i, j, ell; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumRes(CSumOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < num_par ); - CPPAD_ASSERT_UNKNOWN( - arg[0] + arg[1] == arg[ arg[0] + arg[1] + 3 ] - ); - - // Taylor coefficients corresponding to result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - size_t m = (q-1)*r + 1; - Base* z = taylor + i_z * num_taylor_per_var + m; - for(ell = 0; ell < r; ell++) - z[ell] = zero; - Base* x; - i = arg[0]; - j = 2; - while(i--) - { CPPAD_ASSERT_UNKNOWN( size_t(arg[j+1]) < i_z ); - x = taylor + arg[++j] * num_taylor_per_var + m; - for(ell = 0; ell < r; ell++) - z[ell] += x[ell]; - } - i = arg[1]; - while(i--) - { CPPAD_ASSERT_UNKNOWN( size_t(arg[j+1]) < i_z ); - x = taylor + arg[++j] * num_taylor_per_var + m; - for(ell = 0; ell < r; ell++) - z[ell] -= x[ell]; - } -} - -/*! -Compute reverse mode Taylor coefficients for result of op = CsumOp. - -This operation is -\verbatim - z = q + x(1) + ... + x(m) - y(1) - ... - y(n). - H(y, x, w, ...) = G[ z(x, y), y, x, w, ... ] -\endverbatim - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param d -order the highest order Taylor coefficient that we are computing -the partial derivatives with respect to. - -\param i_z -variable index corresponding to the result for this operation; -i.e. the row index in \a taylor corresponding to z. - -\param arg -\a arg[0] -is the number of addition variables in this cummulative summation; i.e., -m. -\n -\a arg[1] -is the number of subtraction variables in this cummulative summation; i.e., -\c m. -\n -parameter[ arg[2] ] -is the parameter value \c q in this cummunative summation. -\n -arg[2+i] -for i = 1 , ... , m is the value x(i). -\n -arg[2+arg[0]+i] -for i = 1 , ... , n is the value y(i). - -\param nc_partial -number of colums in the matrix containing all the partial derivatives. - -\param partial -\b Input: partial [ arg[2+i] * nc_partial + k ] -for i = 1 , ... , m -and k = 0 , ... , d -is the partial derivative of G(z, y, x, w, ...) with respect to the -k-th order Taylor coefficient corresponding to x(i) -\n -\b Input: partial [ arg[2+m+i] * nc_partial + k ] -for i = 1 , ... , n -and k = 0 , ... , d -is the partial derivative of G(z, y, x, w, ...) with respect to the -k-th order Taylor coefficient corresponding to y(i) -\n -\b Input: partial [ i_z * nc_partial + k ] -for i = 1 , ... , n -and k = 0 , ... , d -is the partial derivative of G(z, y, x, w, ...) with respect to the -k-th order Taylor coefficient corresponding to \c z. -\n -\b Output: partial [ arg[2+i] * nc_partial + k ] -for i = 1 , ... , m -and k = 0 , ... , d -is the partial derivative of H(y, x, w, ...) with respect to the -k-th order Taylor coefficient corresponding to x(i) -\n -\b Output: partial [ arg[2+m+i] * nc_partial + k ] -for i = 1 , ... , n -and k = 0 , ... , d -is the partial derivative of H(y, x, w, ...) with respect to the -k-th order Taylor coefficient corresponding to y(i) -*/ - -template -inline void reverse_csum_op( - size_t d , - size_t i_z , - const addr_t* arg , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumRes(CSumOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partial derivative corresponding to result - Base* pz = partial + i_z * nc_partial; - Base* px; - size_t i, j, k; - size_t d1 = d + 1; - i = arg[0]; - j = 2; - while(i--) - { CPPAD_ASSERT_UNKNOWN( size_t(arg[j+1]) < i_z ); - px = partial + arg[++j] * nc_partial; - k = d1; - while(k--) - px[k] += pz[k]; - } - i = arg[1]; - while(i--) - { CPPAD_ASSERT_UNKNOWN( size_t(arg[j+1]) < i_z ); - px = partial + arg[++j] * nc_partial; - k = d1; - while(k--) - px[k] -= pz[k]; - } -} - - -/*! -Forward mode Jacobian sparsity pattern for CSumOp operator. - -This operation is -\verbatim - z = q + x(1) + ... + x(m) - y(1) - ... - y(n). -\endverbatim - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param i_z -variable index corresponding to the result for this operation; -i.e. the index in \a sparsity corresponding to z. - -\param arg -\a arg[0] -is the number of addition variables in this cummulative summation; i.e., -m + n. -\n -\a arg[1] -is the number of subtraction variables in this cummulative summation; i.e., -\c m. -\n -parameter[ arg[2] ] -is the parameter value \c q in this cummunative summation. -\n -arg[2+i] -for i = 1 , ... , m is the value x(i). -\n -arg[2+arg[1]+i] -for i = 1 , ... , n is the value y(i). - -\param sparsity -\b Input: -For i = 1 , ... , m, -the set with index \a arg[2+i] in \a sparsity -is the sparsity bit pattern for x(i). -This identifies which of the independent variables the variable -x(i) depends on. -\n -\b Input: -For i = 1 , ... , n, -the set with index \a arg[2+arg[0]+i] in \a sparsity -is the sparsity bit pattern for x(i). -This identifies which of the independent variables the variable -y(i) depends on. -\n -\b Output: -The set with index \a i_z in \a sparsity -is the sparsity bit pattern for z. -This identifies which of the independent variables the variable z -depends on. -*/ - -template -inline void forward_sparse_jacobian_csum_op( - size_t i_z , - const addr_t* arg , - Vector_set& sparsity ) -{ sparsity.clear(i_z); - - size_t i, j; - i = arg[0] + arg[1]; - j = 2; - while(i--) - { CPPAD_ASSERT_UNKNOWN( size_t(arg[j+1]) < i_z ); - sparsity.binary_union( - i_z , // index in sparsity for result - i_z , // index in sparsity for left operand - arg[++j] , // index for right operand - sparsity // sparsity vector for right operand - ); - } -} - -/*! -Reverse mode Jacobian sparsity pattern for CSumOp operator. - -This operation is -\verbatim - z = q + x(1) + ... + x(m) - y(1) - ... - y(n). - H(y, x, w, ...) = G[ z(x, y), y, x, w, ... ] -\endverbatim - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param i_z -variable index corresponding to the result for this operation; -i.e. the index in \a sparsity corresponding to z. - -\param arg -\a arg[0] -is the number of addition variables in this cummulative summation; i.e., -m + n. -\n -\a arg[1] -is the number of subtraction variables in this cummulative summation; i.e., -\c m. -\n -parameter[ arg[2] ] -is the parameter value \c q in this cummunative summation. -\n -arg[2+i] -for i = 1 , ... , m is the value x(i). -\n -arg[2+arg[1]+i] -for i = 1 , ... , n is the value y(i). - -\param sparsity -For i = 1 , ... , m, -the set with index \a arg[2+i] in \a sparsity -is the sparsity bit pattern for x(i). -This identifies which of the dependent variables depend on x(i). -On input, the sparsity patter corresponds to \c G, -and on ouput it corresponds to \c H. -\n -For i = 1 , ... , m, -the set with index \a arg[2+arg[0]+i] in \a sparsity -is the sparsity bit pattern for y(i). -This identifies which of the dependent variables depend on y(i). -On input, the sparsity patter corresponds to \c G, -and on ouput it corresponds to \c H. -\n -\b Input: -The set with index \a i_z in \a sparsity -is the sparsity bit pattern for z. -On input it corresponds to \c G and on output it is undefined. -*/ - -template -inline void reverse_sparse_jacobian_csum_op( - size_t i_z , - const addr_t* arg , - Vector_set& sparsity ) -{ - size_t i, j; - i = arg[0] + arg[1]; - j = 2; - while(i--) - { ++j; - CPPAD_ASSERT_UNKNOWN( size_t(arg[j]) < i_z ); - sparsity.binary_union( - arg[j] , // index in sparsity for result - arg[j] , // index in sparsity for left operand - i_z , // index for right operand - sparsity // sparsity vector for right operand - ); - } -} -/*! -Reverse mode Hessian sparsity pattern for CSumOp operator. - -This operation is -\verbatim - z = q + x(1) + ... + x(m) - y(1) - ... - y(n). - H(y, x, w, ...) = G[ z(x, y), y, x, w, ... ] -\endverbatim - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param i_z -variable index corresponding to the result for this operation; -i.e. the index in \a sparsity corresponding to z. - -\param arg -\a arg[0] -is the number of addition variables in this cummulative summation; i.e., -m + n. -\n -\a arg[1] -is the number of subtraction variables in this cummulative summation; i.e., -\c m. -\n -parameter[ arg[2] ] -is the parameter value \c q in this cummunative summation. -\n -arg[2+i] -for i = 1 , ... , m is the value x(i). -\n -arg[2+arg[0]+i] -for i = 1 , ... , n is the value y(i). - -\param rev_jacobian -rev_jacobian[i_z] -is all false (true) if the Jabobian of G with respect to z must be zero -(may be non-zero). -\n -\n -For i = 1 , ... , m -rev_jacobian[ arg[2+i] ] -is all false (true) if the Jacobian with respect to x(i) -is zero (may be non-zero). -On input, it corresponds to the function G, -and on output it corresponds to the function H. -\n -\n -For i = 1 , ... , n -rev_jacobian[ arg[2+arg[0]+i] ] -is all false (true) if the Jacobian with respect to y(i) -is zero (may be non-zero). -On input, it corresponds to the function G, -and on output it corresponds to the function H. - -\param rev_hes_sparsity -The set with index \a i_z in in \a rev_hes_sparsity -is the Hessian sparsity pattern for the fucntion G -where one of the partials derivative is with respect to z. -\n -\n -For i = 1 , ... , m -The set with index arg[2+i] in \a rev_hes_sparsity -is the Hessian sparsity pattern -where one of the partials derivative is with respect to x(i). -On input, it corresponds to the function G, -and on output it corresponds to the function H. -\n -\n -For i = 1 , ... , n -The set with index arg[2+arg[0]+i] in \a rev_hes_sparsity -is the Hessian sparsity pattern -where one of the partials derivative is with respect to y(i). -On input, it corresponds to the function G, -and on output it corresponds to the function H. -*/ - -template -inline void reverse_sparse_hessian_csum_op( - size_t i_z , - const addr_t* arg , - bool* rev_jacobian , - Vector_set& rev_hes_sparsity ) -{ - size_t i, j; - i = arg[0] + arg[1]; - j = 2; - while(i--) - { ++j; - CPPAD_ASSERT_UNKNOWN( size_t(arg[j]) < i_z ); - rev_hes_sparsity.binary_union( - arg[j] , // index in sparsity for result - arg[j] , // index in sparsity for left operand - i_z , // index for right operand - rev_hes_sparsity // sparsity vector for right operand - ); - rev_jacobian[arg[j]] |= rev_jacobian[i_z]; - } -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/declare_ad.hpp b/ct_core/include/ct/external/cppad/local/declare_ad.hpp deleted file mode 100644 index 92612693e..000000000 --- a/ct_core/include/ct/external/cppad/local/declare_ad.hpp +++ /dev/null @@ -1,167 +0,0 @@ -// $Id: declare_ad.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_DECLARE_AD_HPP -# define CPPAD_DECLARE_AD_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include -# if CPPAD_USE_CPLUSPLUS_2011 -# include -# endif - -namespace CppAD { - // The conditional expression operator enum type - enum CompareOp - { CompareLt, // less than - CompareLe, // less than or equal - CompareEq, // equal - CompareGe, // greater than or equal - CompareGt, // greater than - CompareNe // not equal - }; - - // simple typedefs - typedef CPPAD_TAPE_ADDR_TYPE addr_t; - typedef CPPAD_TAPE_ID_TYPE tape_id_t; - - // classes - class sparse_jacobian_work; - class sparse_hessian_work; - template class AD; - template class ADFun; - template class ADTape; - template class atomic_base; - template class discrete; - template class player; - template class recorder; - template class VecAD; - template class VecAD_reference; - - // functions with one VecAD argument - template bool Parameter (const VecAD &u); - template bool Variable (const VecAD &u); - - // functions with one AD argument - template int Integer (const AD &u); - template bool Parameter (const AD &u); - template bool Variable (const AD &u); - template bool IdenticalZero (const AD &u); - template bool IdenticalOne (const AD &u); - template bool IdenticalPar (const AD &u); - template bool LessThanZero (const AD &u); - template bool LessThanOrZero (const AD &u); - template bool GreaterThanZero (const AD &u); - template bool GreaterThanOrZero (const AD &u); - template AD Var2Par (const AD &u); - template AD abs (const AD &u); - template AD acos (const AD &u); - template AD asin (const AD &u); - template AD atan (const AD &u); - template AD cos (const AD &u); - template AD cosh (const AD &u); - template AD exp (const AD &u); - template AD log (const AD &u); - template AD log10 (const AD &u); - template AD sin (const AD &u); - template AD sinh (const AD &u); - template AD sqrt (const AD &u); - template AD tan (const AD &u); - - // arithematic operators - template AD operator + ( - const AD &left, const AD &right); - template AD operator - ( - const AD &left, const AD &right); - template AD operator * ( - const AD &left, const AD &right); - template AD operator / ( - const AD &left, const AD &right); - - // comparison operators - template bool operator < ( - const AD &left, const AD &right); - template bool operator <= ( - const AD &left, const AD &right); - template bool operator > ( - const AD &left, const AD &right); - template bool operator >= ( - const AD &left, const AD &right); - template bool operator == ( - const AD &left, const AD &right); - template bool operator != ( - const AD &left, const AD &right); - - // pow - template AD pow ( - const AD &x, const AD &y); - - // azmul - template AD azmul ( - const AD &x, const AD &y); - - // NearEqual - template bool NearEqual( - const AD &x, const AD &y, const Base &r, const Base &a); - - template bool NearEqual( - const Base &x, const AD &y, const Base &r, const Base &a); - - template bool NearEqual( - const AD &x, const Base &y, const Base &r, const Base &a); - - // CondExpOp - template AD CondExpOp ( - enum CompareOp cop , - const AD &left , - const AD &right , - const AD &trueCase , - const AD &falseCase - ); - - // IdenticalEqualPar - template - bool IdenticalEqualPar (const AD &u, const AD &v); - - // EqualOpSeq - template - bool EqualOpSeq (const AD &u, const AD &v); - - // PrintFor - template - void PrintFor( - const AD& flag , - const char* before , - const AD& var , - const char* after - ); - - // Value - template Base Value(const AD &x); - - // Pow function - template AD pow - (const AD &x, const AD &y); - - // input operator - template std::istream& - operator >> (std::istream &is, AD &x); - - // output operator - template std::ostream& - operator << (std::ostream &os, const AD &x); - template std::ostream& - operator << (std::ostream &os, const VecAD_reference &e); - template std::ostream& - operator << (std::ostream &os, const VecAD &vec); -} - -# endif diff --git a/ct_core/include/ct/external/cppad/local/define.hpp b/ct_core/include/ct/external/cppad/local/define.hpp deleted file mode 100644 index 29198c1a1..000000000 --- a/ct_core/include/ct/external/cppad/local/define.hpp +++ /dev/null @@ -1,325 +0,0 @@ -// $Id: define.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_DEFINE_HPP -# define CPPAD_DEFINE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/*! -\file define.hpp -Define processor symbols and macros that are used by CppAD. -*/ - -// ---------------------------------------------------------------------------- -/*! -\def CPPAD_OP_CODE_TYPE -Is the type used to store enum OpCode values. If not the same as OpCode, then -sizeof(CPPAD_OP_CODE_TYPE) <= sizeof( enum OpCode ) -to conserve memory. -This type must support \c std::numeric_limits, -the \c <= operator, -and conversion to \c size_t. -Make sure that the type chosen returns true for is_pod -in pod_vector.hpp. -*/ -# define CPPAD_OP_CODE_TYPE unsigned char - - -// ---------------------------------------------------------------------------- -/*! -\def CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -A version of the inline command that works with MC compiler. - -Microsoft Visual C++ version 9.0 generates a warning if a template -function is declared as a friend -(this was not a problem for version 7.0). -The warning identifier is -\verbatim - warning C4396 -\endverbatim -and it contains the text -\verbatim - the inline specifier cannot be used when a friend declaration refers - to a specialization of a function template -\endverbatim -This happens even if the function is not a specialization. -This macro is defined as empty for Microsoft compilers. -*/ -# ifdef _MSC_VER -# define CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -# else -# define CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION inline -# endif - -// ---------------------------------------------------------------------------- -/*! -\def CPPAD_LIB_EXPORT -Special macro for exporting windows DLL symbols; see -https://cmake.org/Wiki/BuildingWinDLL -*/ -# ifdef _MSC_VER -# ifdef cppad_lib_EXPORTS -# define CPPAD_LIB_EXPORT __declspec(dllexport) -# else -# define CPPAD_LIB_EXPORT __declspec(dllimport) -# endif // cppad_lib_EXPORTS -# else // _MSC_VER -# define CPPAD_LIB_EXPORT -# endif - - -// ============================================================================ -/*! -\def CPPAD_FOLD_ASSIGNMENT_OPERATOR(Op) -Declares automatic coercion for certain AD assignment operations. - -This macro assumes that the operator -\verbatim - left Op right -\endverbatim -is defined for the case where left and right have type AD. -It uses this case to define the cases where -left has type AD and right has type -VecAD_reference, -Base, or -double. -The argument right is const and call by reference. -This macro converts the operands to AD and then -uses the definition of the same operation for that case. -*/ - -# define CPPAD_FOLD_ASSIGNMENT_OPERATOR(Op) \ -/* ----------------------------------------------------------------*/ \ -template \ -inline AD& operator Op \ -(AD &left, double right) \ -{ return left Op AD(right); } \ - \ -template \ -inline AD& operator Op \ -(AD &left, const Base &right) \ -{ return left Op AD(right); } \ - \ -inline AD& operator Op \ -(AD &left, const double &right) \ -{ return left Op AD(right); } \ - \ -template \ -inline AD& operator Op \ -(AD &left, const VecAD_reference &right) \ -{ return left Op right.ADBase(); } - -// ===================================================================== -/*! -\def CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR(Op) -Declares automatic coercion for certain binary operations with AD result. - -This macro assumes that the operator -\verbatim - left Op right -\endverbatim -is defined for the case where left and right -and the result of the operation all -have type AD. -It uses this case to define the cases either left -or right has type VecAD_reference or AD -and the type of the other operand is one of the following: -VecAD_reference, AD, Base, double. -All of the arguments are const and call by reference. -This macro converts the operands to AD and then -uses the definition of the same operation for that case. -*/ -# define CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR(Op) \ -/* ----------------------------------------------------------------*/ \ -/* Operations with VecAD_reference and AD only*/ \ - \ -template \ -inline AD operator Op \ -(const AD &left, const VecAD_reference &right) \ -{ return left Op right.ADBase(); } \ - \ -template \ -inline AD operator Op \ -(const VecAD_reference &left, const VecAD_reference &right)\ -{ return left.ADBase() Op right.ADBase(); } \ - \ -template \ -inline AD operator Op \ - (const VecAD_reference &left, const AD &right) \ -{ return left.ADBase() Op right; } \ -/* ----------------------------------------------------------------*/ \ -/* Operations Base */ \ - \ -template \ -inline AD operator Op \ - (const Base &left, const AD &right) \ -{ return AD(left) Op right; } \ - \ -template \ -inline AD operator Op \ - (const Base &left, const VecAD_reference &right) \ -{ return AD(left) Op right.ADBase(); } \ - \ -template \ -inline AD operator Op \ - (const AD &left, const Base &right) \ -{ return left Op AD(right); } \ - \ -template \ -inline AD operator Op \ - (const VecAD_reference &left, const Base &right) \ -{ return left.ADBase() Op AD(right); } \ - \ -/* ----------------------------------------------------------------*/ \ -/* Operations double */ \ - \ -template \ -inline AD operator Op \ - (const double &left, const AD &right) \ -{ return AD(left) Op right; } \ - \ -template \ -inline AD operator Op \ - (const double &left, const VecAD_reference &right) \ -{ return AD(left) Op right.ADBase(); } \ - \ -template \ -inline AD operator Op \ - (const AD &left, const double &right) \ -{ return left Op AD(right); } \ - \ -template \ -inline AD operator Op \ - (const VecAD_reference &left, const double &right) \ -{ return left.ADBase() Op AD(right); } \ -/* ----------------------------------------------------------------*/ \ -/* Special case to avoid ambuigity when Base is double */ \ - \ -inline AD operator Op \ - (const double &left, const AD &right) \ -{ return AD(left) Op right; } \ - \ -inline AD operator Op \ - (const double &left, const VecAD_reference &right) \ -{ return AD(left) Op right.ADBase(); } \ - \ -inline AD operator Op \ - (const AD &left, const double &right) \ -{ return left Op AD(right); } \ - \ -inline AD operator Op \ - (const VecAD_reference &left, const double &right) \ -{ return left.ADBase() Op AD(right); } - -// ======================================================================= - -/*! -\def CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(Op) -Declares automatic coercion for certain binary operations with bool result. - -This macro assumes that the operator -\verbatim - left Op right -\endverbatim -is defined for the case where left and right -have type AD and the result has type bool. -It uses this case to define the cases either left -or right has type -VecAD_reference or AD -and the type of the other operand is one of the following: -VecAD_reference, AD, Base, double. -All of the arguments are const and call by reference. -This macro converts the operands to AD and then -uses the definition of the same operation for that case. -*/ -# define CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR(Op) \ -/* ----------------------------------------------------------------*/ \ -/* Operations with VecAD_reference and AD only*/ \ - \ -template \ -inline bool operator Op \ -(const AD &left, const VecAD_reference &right) \ -{ return left Op right.ADBase(); } \ - \ -template \ -inline bool operator Op \ -(const VecAD_reference &left, const VecAD_reference &right)\ -{ return left.ADBase() Op right.ADBase(); } \ - \ -template \ -inline bool operator Op \ - (const VecAD_reference &left, const AD &right) \ -{ return left.ADBase() Op right; } \ -/* ----------------------------------------------------------------*/ \ -/* Operations Base */ \ - \ -template \ -inline bool operator Op \ - (const Base &left, const AD &right) \ -{ return AD(left) Op right; } \ - \ -template \ -inline bool operator Op \ - (const Base &left, const VecAD_reference &right) \ -{ return AD(left) Op right.ADBase(); } \ - \ -template \ -inline bool operator Op \ - (const AD &left, const Base &right) \ -{ return left Op AD(right); } \ - \ -template \ -inline bool operator Op \ - (const VecAD_reference &left, const Base &right) \ -{ return left.ADBase() Op AD(right); } \ - \ -/* ----------------------------------------------------------------*/ \ -/* Operations double */ \ - \ -template \ -inline bool operator Op \ - (const double &left, const AD &right) \ -{ return AD(left) Op right; } \ - \ -template \ -inline bool operator Op \ - (const double &left, const VecAD_reference &right) \ -{ return AD(left) Op right.ADBase(); } \ - \ -template \ -inline bool operator Op \ - (const AD &left, const double &right) \ -{ return left Op AD(right); } \ - \ -template \ -inline bool operator Op \ - (const VecAD_reference &left, const double &right) \ -{ return left.ADBase() Op AD(right); } \ -/* ----------------------------------------------------------------*/ \ -/* Special case to avoid ambuigity when Base is double */ \ - \ -inline bool operator Op \ - (const double &left, const AD &right) \ -{ return AD(left) Op right; } \ - \ -inline bool operator Op \ - (const double &left, const VecAD_reference &right) \ -{ return AD(left) Op right.ADBase(); } \ - \ -inline bool operator Op \ - (const AD &left, const double &right) \ -{ return left Op AD(right); } \ - \ -inline bool operator Op \ - (const VecAD_reference &left, const double &right) \ -{ return left.ADBase() Op AD(right); } - -# endif diff --git a/ct_core/include/ct/external/cppad/local/dependent.hpp b/ct_core/include/ct/external/cppad/local/dependent.hpp deleted file mode 100644 index ec922fdea..000000000 --- a/ct_core/include/ct/external/cppad/local/dependent.hpp +++ /dev/null @@ -1,332 +0,0 @@ -// $Id: dependent.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_DEPENDENT_HPP -# define CPPAD_DEPENDENT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin Dependent$$ -$spell - alloc - num - taylor_ - ADvector - const -$$ - -$spell -$$ - -$section Stop Recording and Store Operation Sequence$$ -$mindex ADFun tape Dependent$$ - - -$head Syntax$$ -$icode%f%.Dependent(%x%, %y%)%$$ - -$head Purpose$$ -Stop recording and the AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$ -that started with the call -$codei% - Independent(%x%) -%$$ -and store the operation sequence in $icode f$$. -The operation sequence defines an -$cref/AD function/glossary/AD Function/$$ -$latex \[ - F : B^n \rightarrow B^m -\] $$ -where $latex B$$ is the space corresponding to objects of type $icode Base$$. -The value $latex n$$ is the dimension of the -$cref/domain/seq_property/Domain/$$ space for the operation sequence. -The value $latex m$$ is the dimension of the -$cref/range/seq_property/Range/$$ space for the operation sequence -(which is determined by the size of $icode y$$). - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -The AD of $icode Base$$ operation sequence is stored in $icode f$$; i.e., -it becomes the operation sequence corresponding to $icode f$$. -If a previous operation sequence was stored in $icode f$$, -it is deleted. - -$head x$$ -The argument $icode x$$ -must be the vector argument in a previous call to -$cref Independent$$. -Neither its size, or any of its values, are allowed to change -between calling -$codei% - Independent(%x%) -%$$ -and -$codei% - %f%.Dependent(%x%, %y%) -%$$. - -$head y$$ -The vector $icode y$$ has prototype -$codei% - const %ADvector% &%y% -%$$ -(see $cref/ADvector/FunConstruct/$$ below). -The length of $icode y$$ must be greater than zero -and is the dimension of the range space for $icode f$$. - -$head ADvector$$ -The type $icode ADvector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$codei%AD<%Base%>%$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Taping$$ -The tape, -that was created when $codei%Independent(%x%)%$$ was called, -will stop recording. -The AD operation sequence will be transferred from -the tape to the object $icode f$$ and the tape will then be deleted. - -$head Forward$$ -No $cref Forward$$ calculation is preformed during this operation. -Thus, directly after this operation, -$codei% - %f%.size_order() -%$$ -is zero (see $cref size_order$$). - -$head Parallel Mode$$ -The call to $code Independent$$, -and the corresponding call to -$codei% - ADFun<%Base%> %f%( %x%, %y%) -%$$ -or -$codei% - %f%.Dependent( %x%, %y%) -%$$ -or $cref abort_recording$$, -must be preformed by the same thread; i.e., -$cref/thread_alloc::thread_num/ta_thread_num/$$ must be the same. - -$head Example$$ -The file -$cref fun_check.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ----------------------------------------------------------------------------- -*/ - - -// BEGIN CppAD namespace -namespace CppAD { - -/*! -\file dependent.hpp -Different versions of Dependent function. -*/ - -/*! -Determine the \c tape corresponding to this exeuction thread and then use -Dependent(tape, y) to store this tapes recording in a function. - -\param y [in] -The dependent variable vector for the corresponding function. -*/ -template -template -void ADFun::Dependent(const ADvector &y) -{ ADTape* tape = AD::tape_ptr(); - CPPAD_ASSERT_KNOWN( - tape != CPPAD_NULL, - "Can't store current operation sequence in this ADFun object" - "\nbecause there is no active tape (for this thread)." - ); - - // code above just determines the tape and checks for errors - Dependent(tape, y); -} - - -/*! -Determine the \c tape corresponding to this exeuction thread and then use -Dependent(tape, y) to store this tapes recording in a function. - -\param x [in] -The independent variable vector for this tape. This informaiton is -also stored in the tape so a check is done to make sure it is correct -(if NDEBUG is not defined). - -\param y [in] -The dependent variable vector for the corresponding function. -*/ -template -template -void ADFun::Dependent(const ADvector &x, const ADvector &y) -{ - CPPAD_ASSERT_KNOWN( - x.size() > 0, - "Dependent: independent variable vector has size zero." - ); - CPPAD_ASSERT_KNOWN( - Variable(x[0]), - "Dependent: independent variable vector has been changed." - ); - ADTape *tape = AD::tape_ptr(x[0].tape_id_); - CPPAD_ASSERT_KNOWN( - tape->size_independent_ == size_t( x.size() ), - "Dependent: independent variable vector has been changed." - ); -# ifndef NDEBUG - size_t i, j; - for(j = 0; j < size_t(x.size()); j++) - { CPPAD_ASSERT_KNOWN( - size_t(x[j].taddr_) == (j+1), - "ADFun: independent variable vector has been changed." - ); - CPPAD_ASSERT_KNOWN( - x[j].tape_id_ == x[0].tape_id_, - "ADFun: independent variable vector has been changed." - ); - } - for(i = 0; i < size_t(y.size()); i++) - { CPPAD_ASSERT_KNOWN( - CppAD::Parameter( y[i] ) | (y[i].tape_id_ == x[0].tape_id_) , - "ADFun: dependent vector contains a variable for" - "\na different tape (thread) than the independent variables." - ); - } -# endif - - // code above just determines the tape and checks for errors - Dependent(tape, y); -} - -/*! -Replace the floationg point operations sequence for this function object. - -\param tape -is a tape that contains the new floating point operation sequence -for this function. -After this operation, all memory allocated for this tape is deleted. - -\param y -The dependent variable vector for the function being stored in this object. - -\par -All of the private member data in ad_fun.hpp is set to correspond to the -new tape except for check_for_nan_. -*/ - -template -template -void ADFun::Dependent(ADTape *tape, const ADvector &y) -{ - size_t m = y.size(); - size_t n = tape->size_independent_; - size_t i, j; - size_t y_taddr; - - // check ADvector is Simple Vector class with AD elements - CheckSimpleVector< AD, ADvector>(); - - CPPAD_ASSERT_KNOWN( - y.size() > 0, - "ADFun operation sequence dependent variable size is zero size" - ); - // --------------------------------------------------------------------- - // Begin setting ad_fun.hpp private member data - // --------------------------------------------------------------------- - // dep_parameter_, dep_taddr_ - CPPAD_ASSERT_UNKNOWN( NumRes(ParOp) == 1 ); - dep_parameter_.resize(m); - dep_taddr_.resize(m); - for(i = 0; i < m; i++) - { dep_parameter_[i] = CppAD::Parameter(y[i]); - if( dep_parameter_[i] ) - { // make a tape copy of dependent variables that are parameters, - y_taddr = tape->RecordParOp( y[i].value_ ); - } - else y_taddr = y[i].taddr_; - - CPPAD_ASSERT_UNKNOWN( y_taddr > 0 ); - dep_taddr_[i] = y_taddr; - } - - // put an EndOp at the end of the tape - tape->Rec_.PutOp(EndOp); - - // some size_t values in ad_fun.hpp - has_been_optimized_ = false; - compare_change_count_ = 1; - compare_change_number_ = 0; - compare_change_op_index_ = 0; - num_order_taylor_ = 0; - num_direction_taylor_ = 0; - cap_order_taylor_ = 0; - - // num_var_tape_ - // Now that all the variables are in the tape, we can set this value. - num_var_tape_ = tape->Rec_.num_var_rec(); - - // taylor_ - taylor_.erase(); - - // cskip_op_ - cskip_op_.erase(); - cskip_op_.extend( tape->Rec_.num_op_rec() ); - - // load_op_ - load_op_.erase(); - load_op_.extend( tape->Rec_.num_load_op_rec() ); - - // play_ - // Now that each dependent variable has a place in the tape, - // and there is a EndOp at the end of the tape, we can transfer the - // recording to the player and and erase the tape. - play_.get(tape->Rec_); - - // ind_taddr_ - // Note that play_ has been set, we can use it to check operators - ind_taddr_.resize(n); - CPPAD_ASSERT_UNKNOWN( n < num_var_tape_); - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( play_.GetOp(j+1) == InvOp ); - ind_taddr_[j] = j+1; - } - - // for_jac_sparse_pack_, for_jac_sparse_set_ - for_jac_sparse_pack_.resize(0, 0); - for_jac_sparse_set_.resize(0,0); - // --------------------------------------------------------------------- - // End set ad_fun.hpp private member data - // --------------------------------------------------------------------- - - // now we can delete the tape - AD::tape_manage(tape_manage_delete); - - // total number of varables in this recording - CPPAD_ASSERT_UNKNOWN( num_var_tape_ == play_.num_var_rec() ); - - // used to determine if there is an operation sequence in *this - CPPAD_ASSERT_UNKNOWN( num_var_tape_ > 0 ); - -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/discrete.hpp b/ct_core/include/ct/external/cppad/local/discrete.hpp deleted file mode 100644 index 19c44e8e0..000000000 --- a/ct_core/include/ct/external/cppad/local/discrete.hpp +++ /dev/null @@ -1,303 +0,0 @@ -// $Id: discrete.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_DISCRETE_HPP -# define CPPAD_DISCRETE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Discrete$$ -$spell - retaping - namespace - std - Eq - Cpp - const - inline - Geq -$$ - -$section Discrete AD Functions$$ -$mindex CPPAD_DISCRETE_FUNCTION$$ - - -$head Syntax$$ -$codei%CPPAD_DISCRETE_FUNCTION(%Base%, %name%) -%$$ -$icode%y% = %name%(%x%) -%$$ -$icode%ay% = %name%(%ax%) -%$$ - - -$head Purpose$$ -Record the evaluation of a discrete function as part -of an $codei%AD<%Base%>%$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. -The value of a discrete function can depend on the -$cref/independent variables/glossary/Tape/Independent Variable/$$, -but its derivative is identically zero. -For example, suppose that the integer part of -a $cref/variable/glossary/Variable/$$ $icode x$$ is the -index into an array of values. - -$head Base$$ -This is the -$cref/base type/base_require/$$ -corresponding to the operations sequence; -i.e., use of the $icode name$$ with arguments of type -$codei%AD<%Base%>%$$ can be recorded in an operation sequence. - -$head name$$ -This is the name of the function (as it is used in the source code). -The user must provide a version of $icode name$$ -where the argument has type $icode Base$$. -CppAD uses this to create a version of $icode name$$ -where the argument has type $codei%AD<%Base%>%$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Base%& %x% -%$$ -It is the value at which the user provided version of $icode name$$ -is to be evaluated. - -$head y$$ -The result $icode y$$ has prototype -$codei% - %Base% %y% -%$$ -It is the return value for the user provided version of $icode name$$. - -$head ax$$ -The argument $icode ax$$ has prototype -$codei% - const AD<%Base%>& %ax% -%$$ -It is the value at which the CppAD provided version of $icode name$$ -is to be evaluated. - -$head ay$$ -The result $icode ay$$ has prototype -$codei% - AD<%Base%> %ay% -%$$ -It is the return value for the CppAD provided version of $icode name$$. - - -$head Create AD Version$$ -The preprocessor macro invocation -$codei% - CPPAD_DISCRETE_FUNCTION(%Base%, %name%) -%$$ -defines the $codei%AD<%Base%>%$$ version of $icode name$$. -This can be with in a namespace (not the $code CppAD$$ namespace) -but must be outside of any routine. - -$head Operation Sequence$$ -This is an AD of $icode Base$$ -$cref/atomic operation/glossary/Operation/Atomic/$$ -and hence is part of the current -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Derivatives$$ -During a zero order $cref Forward$$ operation, -an $cref ADFun$$ object will compute the value of $icode name$$ -using the user provided $icode Base$$ version of this routine. -All the derivatives of $icode name$$ will be evaluated as zero. - -$head Parallel Mode$$ -The first call to -$codei% - %ay% = %name%(%ax%) -%$$ -must not be in $cref/parallel/ta_in_parallel/$$ execution mode. - - -$head Example$$ -$children% - example/tape_index.cpp% - example/interp_onetape.cpp% - example/interp_retape.cpp -%$$ -The file -$cref tape_index.cpp$$ -contains an example and test that uses a discrete function -to vary an array index during $cref Forward$$ mode calculations. -The file -$cref interp_onetape.cpp$$ -contains an example and test that uses discrete -functions to avoid retaping a calculation that requires interpolation. -(The file -$cref interp_retape.cpp$$ -shows how interpolation can be done with retaping.) - -$head CppADCreateDiscrete Deprecated 2007-07-28$$ -The preprocessor symbol $code CppADCreateDiscrete$$ -is defined to be the same as $code CPPAD_DISCRETE_FUNCTION$$ -but its use is deprecated. - -$end ------------------------------------------------------------------------------- -*/ -# include -# include - -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file discrete.hpp -user define discrete functions -*/ - -/*! -\def CPPAD_DISCRETE_FUNCTION(Base, name) -Defines the function name(ax, ay) -where \c ax and \c ay are vectors with AD elements. - -\par Base -is the base type for the discrete function. - -\par name -is the name of the user defined function that corresponding to this operation. -*/ - -# define CPPAD_DISCRETE_FUNCTION(Base, name) \ -inline CppAD::AD name (const CppAD::AD& ax) \ -{ \ - static CppAD::discrete fun(#name, name); \ - \ - return fun.ad(ax); \ -} -# define CppADCreateDiscrete CPPAD_DISCRETE_FUNCTION - - -/* -Class that acutally implemnets the ay = name(ax) call. - -A new discrete function is generated for ech time the user invokes -the CPPAD_DISCRETE_FUNCTION macro; see static object in that macro. -*/ -template -class discrete { - /// parallel_ad needs to call List to initialize static - template - friend void parallel_ad(void); - - /// type for the user routine that computes function values - typedef Base (*F) (const Base& x); -private: - /// name of this user defined function - const std::string name_; - /// user's implementation of the function for Base operations - const F f_; - /// index of this objec in the vector of all objects for this class - const size_t index_; - - /*! - List of all objects in this class. - - If we use CppAD::vector for this vector, it will appear that - there is a memory leak because this list is not distroyed before - thread_alloc::free_available(thread) is called by the testing routines. - */ - static std::vector& List(void) - { CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static std::vector list; - return list; - } -public: - /*! - Constructor called for each invocation of CPPAD_DISCRETE_FUNCTION. - - Put this object in the list of all objects for this class and set - the constant private data name_, f_, and index_. - - \param Name - is the user's name for this discrete function. - - \param f - user routine that implements this function for \c Base class. - - \par - This constructor can ont be used in parallel mode because it changes - the static object \c List. - */ - discrete(const char* Name, F f) : - name_(Name) - , f_(f) - , index_( List().size() ) - { - CPPAD_ASSERT_KNOWN( - ! thread_alloc::in_parallel() , - "discrete: First call the function *Name is in parallel mode." - ); - List().push_back(this); - } - - /*! - Implement the user call to ay = name(ax). - - \param ax - is the argument for this call. - - \return - the return value is called \c ay above. - */ - AD ad(const AD &ax) const - { AD ay; - - ay.value_ = f_(ax.value_); - if( Variable(ax) ) - { ADTape *tape = ax.tape_this(); - CPPAD_ASSERT_UNKNOWN( NumRes(DisOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(DisOp) == 2 ); - - // put operand addresses in the tape - tape->Rec_.PutArg(index_, ax.taddr_); - // put operator in the tape - ay.taddr_ = tape->Rec_.PutOp(DisOp); - // make result a variable - ay.tape_id_ = tape->id_; - - CPPAD_ASSERT_UNKNOWN( Variable(ay) ); - } - return ay; - } - - /// Name corresponding to a discrete object - static const char* name(size_t index) - { return List()[index]->name_.c_str(); } - - /*! - Link from forward mode sweep to users routine - - \param index - index for this function in the list of all discrete object - - \param x - argument value at which to evaluate this function - */ - static Base eval(size_t index, const Base& x) - { - CPPAD_ASSERT_UNKNOWN(index < List().size() ); - - return List()[index]->f_(x); - } -}; - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/discrete_op.hpp b/ct_core/include/ct/external/cppad/local/discrete_op.hpp deleted file mode 100644 index 80dffe74b..000000000 --- a/ct_core/include/ct/external/cppad/local/discrete_op.hpp +++ /dev/null @@ -1,122 +0,0 @@ -// $Id: discrete_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_DISCRETE_OP_HPP -# define CPPAD_DISCRETE_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file discrete_op.hpp -Forward mode for z = f(x) where f is piecewise constant. -*/ - - -/*! -forward mode Taylor coefficient for result of op = DisOp. - -The C++ source code corresponding to this operation is -\verbatim - z = f(x) -\endverbatim -where f is a piecewise constant function (and it's derivative is always -calculated as zero). - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base . - -\param p -is the lowest order Taylor coefficient that will be calculated. - -\param q -is the highest order Taylor coefficient that will be calculated. - -\param r -is the number of directions, for each order, -that will be calculated (except for order zero wich only has one direction). - -\param i_z -variable index corresponding to the result for this operation; -i.e. the row index in \a taylor corresponding to z. - -\param arg -\a arg[0] -\n -is the index, in the order of the discrete functions defined by the user, -for this discrete function. -\n -\n -\a arg[1] -variable index corresponding to the argument for this operator; -i.e. the row index in \a taylor corresponding to x. - -\param cap_order -maximum number of orders that will fit in the taylor array. - -\par tpv -We use the notation -tpv = (cap_order-1) * r + 1 -which is the number of Taylor coefficients per variable - -\param taylor -\b Input: taylor [ arg[1] * tpv + 0 ] -is the zero order Taylor coefficient corresponding to x. -\n -\b Output: if p == 0 -taylor [ i_z * tpv + 0 ] -is the zero order Taylor coefficient corresponding to z. -For k = max(p, 1), ... , q, -taylor [ i_z * tpv + (k-1)*r + 1 + ell ] -is the k-th order Taylor coefficient corresponding to z -(which is zero). - -\par Checked Assertions where op is the unary operator with one result: -\li NumArg(op) == 2 -\li NumRes(op) == 1 -\li q < cap_order -\li 0 < r -*/ -template -inline void forward_dis_op( - size_t p , - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(DisOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(DisOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( 0 < r ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + arg[1] * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - - if( p == 0 ) - { z[0] = discrete::eval(arg[0], x[0]); - p++; - } - for(size_t ell = 0; ell < r; ell++) - for(size_t k = p; k <= q; k++) - z[ (k-1) * r + 1 + ell ] = Base(0); -} - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/div.hpp b/ct_core/include/ct/external/cppad/local/div.hpp deleted file mode 100644 index 74b7083de..000000000 --- a/ct_core/include/ct/external/cppad/local/div.hpp +++ /dev/null @@ -1,101 +0,0 @@ -// $Id: div.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_DIV_HPP -# define CPPAD_DIV_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD operator / (const AD &left , const AD &right) -{ - // compute the Base part - AD result; - result.value_ = left.value_ / right.value_; - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - // check if there is a recording in progress - ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return result; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = left.tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // result = variable / variable - CPPAD_ASSERT_KNOWN( - left.tape_id_ == right.tape_id_, - "Dividing AD objects that are" - " variables on different tapes." - ); - CPPAD_ASSERT_UNKNOWN( NumRes(DivvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(DivvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(left.taddr_, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(DivvvOp); - // make result a variable - result.tape_id_ = tape_id; - } - else if( IdenticalOne(right.value_) ) - { // result = variable / 1 - result.make_variable(left.tape_id_, left.taddr_); - } - else - { // result = variable / parameter - CPPAD_ASSERT_UNKNOWN( NumRes(DivvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(DivvpOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(left.taddr_, p); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(DivvpOp); - // make result a variable - result.tape_id_ = tape_id; - } - } - else if( var_right ) - { if( IdenticalZero(left.value_) ) - { // result = 0 / variable - } - else - { // result = parameter / variable - CPPAD_ASSERT_UNKNOWN( NumRes(DivpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(DivpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left.value_); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(DivpvOp); - // make result a variable - result.tape_id_ = tape_id; - } - } - return result; -} - -// convert other cases into the case above -CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR(/) - - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/div_eq.hpp b/ct_core/include/ct/external/cppad/local/div_eq.hpp deleted file mode 100644 index bcedaecd7..000000000 --- a/ct_core/include/ct/external/cppad/local/div_eq.hpp +++ /dev/null @@ -1,93 +0,0 @@ -// $Id: div_eq.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_DIV_EQ_HPP -# define CPPAD_DIV_EQ_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD& AD::operator /= (const AD &right) -{ - // compute the Base part - Base left; - left = value_; - value_ /= right.value_; - - // check if there is a recording in progress - ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return *this; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // this = variable / variable - CPPAD_ASSERT_UNKNOWN( NumRes(DivvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(DivvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(taddr_, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(DivvvOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - else if( IdenticalOne( right.value_ ) ) - { // this = variable * 1 - } - else - { // this = variable / parameter - CPPAD_ASSERT_UNKNOWN( NumRes(DivvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(DivvpOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(taddr_, p); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(DivvpOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - } - else if( var_right ) - { if( IdenticalZero(left) ) - { // this = 0 / variable - } - else - { // this = parameter / variable - CPPAD_ASSERT_UNKNOWN( NumRes(DivpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(DivpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(DivpvOp); - // make this a variable - tape_id_ = tape_id; - } - } - return *this; -} - -CPPAD_FOLD_ASSIGNMENT_OPERATOR(/=) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/div_op.hpp b/ct_core/include/ct/external/cppad/local/div_op.hpp deleted file mode 100644 index e27dbfbfa..000000000 --- a/ct_core/include/ct/external/cppad/local/div_op.hpp +++ /dev/null @@ -1,575 +0,0 @@ -// $Id: div_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_DIV_OP_HPP -# define CPPAD_DIV_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file div_op.hpp -Forward and reverse mode calculations for z = x / y. -*/ - -// --------------------------- Divvv ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = DivvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x / y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_binary_op -*/ - -template -inline void forward_divvv_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(DivvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(DivvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - - // Using CondExp, it can make sense to divide by zero, - // so do not make it an error. - size_t k; - for(size_t d = p; d <= q; d++) - { z[d] = x[d]; - for(k = 1; k <= d; k++) - z[d] -= z[d-k] * y[k]; - z[d] /= y[0]; - } -} -/*! -Multiple directions forward mode Taylor coefficients for op = DivvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x / y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_binary_op_dir -*/ - -template -inline void forward_divvv_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(DivvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(DivvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to arguments and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + arg[0] * num_taylor_per_var; - Base* y = taylor + arg[1] * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - - - // Using CondExp, it can make sense to divide by zero, - // so do not make it an error. - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - { z[m+ell] = x[m+ell] - z[0] * y[m+ell]; - for(size_t k = 1; k < q; k++) - z[m+ell] -= z[(q-k-1)*r+1+ell] * y[(k-1)*r+1+ell]; - z[m+ell] /= y[0]; - } -} - - -/*! -Compute zero order forward mode Taylor coefficients for result of op = DivvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x / y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_binary_op_0 -*/ - -template -inline void forward_divvv_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(DivvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(DivvvOp) == 1 ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = x[0] / y[0]; -} - -/*! -Compute reverse mode partial derivatives for result of op = DivvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x / y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails reverse_binary_op -*/ - -template -inline void reverse_divvv_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(DivvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(DivvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Arguments - const Base* y = taylor + arg[1] * cap_order; - const Base* z = taylor + i_z * cap_order; - - // Partial derivatives corresponding to arguments and result - Base* px = partial + arg[0] * nc_partial; - Base* py = partial + arg[1] * nc_partial; - Base* pz = partial + i_z * nc_partial; - - // Using CondExp, it can make sense to divide by zero - // so do not make it an error. - Base inv_y0 = Base(1) / y[0]; - - size_t k; - // number of indices to access - size_t j = d + 1; - while(j) - { --j; - // scale partial w.r.t. z[j] - pz[j] = azmul(pz[j], inv_y0); - - px[j] += pz[j]; - for(k = 1; k <= j; k++) - { pz[j-k] -= azmul(pz[j], y[k] ); - py[k] -= azmul(pz[j], z[j-k]); - } - py[0] -= azmul(pz[j], z[j]); - } -} - -// --------------------------- Divpv ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = DivpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x / y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op -*/ - -template -inline void forward_divpv_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(DivpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(DivpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to arguments and result - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - // Paraemter value - Base x = parameter[ arg[0] ]; - - // Using CondExp, it can make sense to divide by zero, - // so do not make it an error. - size_t k; - if( p == 0 ) - { z[0] = x / y[0]; - p++; - } - for(size_t d = p; d <= q; d++) - { z[d] = Base(0); - for(k = 1; k <= d; k++) - z[d] -= z[d-k] * y[k]; - z[d] /= y[0]; - } -} -/*! -Multiple directions forward mode Taylor coefficients for op = DivpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x / y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op_dir -*/ - -template -inline void forward_divpv_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(DivpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(DivpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to arguments and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* y = taylor + arg[1] * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - - // Using CondExp, it can make sense to divide by zero, - // so do not make it an error. - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - { z[m+ell] = - z[0] * y[m+ell]; - for(size_t k = 1; k < q; k++) - z[m+ell] -= z[(q-k-1)*r+1+ell] * y[(k-1)*r+1+ell]; - z[m+ell] /= y[0]; - } -} - -/*! -Compute zero order forward mode Taylor coefficient for result of op = DivpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x / y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op_0 -*/ - -template -inline void forward_divpv_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(DivpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(DivpvOp) == 1 ); - - // Paraemter value - Base x = parameter[ arg[0] ]; - - // Taylor coefficients corresponding to arguments and result - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = x / y[0]; -} - -/*! -Compute reverse mode partial derivative for result of op = DivpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x / y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails reverse_binary_op -*/ - -template -inline void reverse_divpv_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(DivvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(DivvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Arguments - const Base* y = taylor + arg[1] * cap_order; - const Base* z = taylor + i_z * cap_order; - - // Partial derivatives corresponding to arguments and result - Base* py = partial + arg[1] * nc_partial; - Base* pz = partial + i_z * nc_partial; - - // Using CondExp, it can make sense to divide by zero so do not - // make it an error. - Base inv_y0 = Base(1) / y[0]; - - size_t k; - // number of indices to access - size_t j = d + 1; - while(j) - { --j; - // scale partial w.r.t z[j] - pz[j] = azmul(pz[j], inv_y0); - - for(k = 1; k <= j; k++) - { pz[j-k] -= azmul(pz[j], y[k] ); - py[k] -= azmul(pz[j], z[j-k] ); - } - py[0] -= azmul(pz[j], z[j]); - } -} - - -// --------------------------- Divvp ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = DivvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x / y -\endverbatim -In the documentation below, -this operations is for the case where x is a variable and y is a parameter. - -\copydetails forward_binary_op -*/ - -template -inline void forward_divvp_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(DivvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(DivvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* z = taylor + i_z * cap_order; - - // Parameter value - Base y = parameter[ arg[1] ]; - - // Using CondExp and multiple levels of AD, it can make sense - // to divide by zero so do not make it an error. - for(size_t d = p; d <= q; d++) - z[d] = x[d] / y; -} -/*! -Multiple direction forward mode Taylor coefficients for op = DivvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x / y -\endverbatim -In the documentation below, -this operations is for the case where x is a variable and y is a parameter. - -\copydetails forward_binary_op_dir -*/ - -template -inline void forward_divvp_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(DivvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(DivvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - - // Taylor coefficients corresponding to arguments and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + arg[0] * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - - // Parameter value - Base y = parameter[ arg[1] ]; - - // Using CondExp and multiple levels of AD, it can make sense - // to divide by zero so do not make it an error. - size_t m = (q-1)*r + 1; - for(size_t ell = 0; ell < r; ell++) - z[m + ell] = x[m + ell] / y; -} - - -/*! -Compute zero order forward mode Taylor coefficients for result of op = DivvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x / y -\endverbatim -In the documentation below, -this operations is for the case where x is a variable and y is a parameter. - -\copydetails forward_binary_op_0 -*/ - -template -inline void forward_divvp_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(DivvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(DivvpOp) == 1 ); - - // Parameter value - Base y = parameter[ arg[1] ]; - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = x[0] / y; -} - -/*! -Compute reverse mode partial derivative for result of op = DivvpOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x / y -\endverbatim -In the documentation below, -this operations is for the case where x is a variable and y is a parameter. - -\copydetails reverse_binary_op -*/ - -template -inline void reverse_divvp_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(DivvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(DivvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Argument values - Base y = parameter[ arg[1] ]; - - // Partial derivatives corresponding to arguments and result - Base* px = partial + arg[0] * nc_partial; - Base* pz = partial + i_z * nc_partial; - - // Using CondExp, it can make sense to divide by zero - // so do not make it an error. - Base inv_y = Base(1) / y; - - // number of indices to access - size_t j = d + 1; - while(j) - { --j; - px[j] += azmul(pz[j], inv_y); - } -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/drivers.hpp b/ct_core/include/ct/external/cppad/local/drivers.hpp deleted file mode 100644 index 29f253a88..000000000 --- a/ct_core/include/ct/external/cppad/local/drivers.hpp +++ /dev/null @@ -1,48 +0,0 @@ -// $Id: drivers.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_DRIVERS_HPP -# define CPPAD_DRIVERS_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Drivers$$ -$spell -$$ - - -$section First and Second Derivatives: Easy Drivers$$ -$mindex forward reverse$$ - - -$childtable% - cppad/local/jacobian.hpp% - cppad/local/for_one.hpp% - cppad/local/rev_one.hpp% - cppad/local/hessian.hpp% - cppad/local/for_two.hpp% - cppad/local/rev_two.hpp% - cppad/local/sparse_jacobian.hpp% - cppad/local/sparse_hessian.hpp -%$$ - -$end -*/ -# include -# include -# include -# include -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/local/epsilon.hpp b/ct_core/include/ct/external/cppad/local/epsilon.hpp deleted file mode 100644 index 537f27d82..000000000 --- a/ct_core/include/ct/external/cppad/local/epsilon.hpp +++ /dev/null @@ -1,60 +0,0 @@ -// $Id: epsilon.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_EPSILON_HPP -# define CPPAD_EPSILON_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ------------------------------------------------------------------------------- -$begin epsilon$$ -$spell - std - eps - CppAD - namespace - const -$$ - -$section Machine Epsilon For AD Types$$ - -$head Deprecated 2012-06-17$$ -This routine has been deprecated. -You should use the $cref numeric_limits$$ $code epsilon$$ instead. - -$head Syntax$$ -$icode%eps% = epsilon<%Float%>()%$$ - -$head Purpose$$ -Obtain the value of machine epsilon corresponding -to the type $icode%Float%$$. - -$head Float$$ -this type can either be $codei%AD<%Base%>%$$, -or it can be $icode Base$$ for any $codei%AD<%Base%>%$$ type. - -$head eps$$ -The result $icode eps$$ has prototype -$codei% - %Float% eps -%$$ - -$end ------------------------------------------------------------------------------- -*/ - -namespace CppAD { - - template - inline Type epsilon(void) - { return Type ( numeric_limits::epsilon() ); } - -} -# endif diff --git a/ct_core/include/ct/external/cppad/local/equal_op_seq.hpp b/ct_core/include/ct/external/cppad/local/equal_op_seq.hpp deleted file mode 100644 index 4cf390e4e..000000000 --- a/ct_core/include/ct/external/cppad/local/equal_op_seq.hpp +++ /dev/null @@ -1,120 +0,0 @@ -// $Id: equal_op_seq.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_EQUAL_OP_SEQ_HPP -# define CPPAD_EQUAL_OP_SEQ_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ------------------------------------------------------------------------------- -$begin EqualOpSeq$$ -$spell - Op - const - bool -$$ - - -$section Check if Two Value are Identically Equal$$ -$mindex EqualOpSeq operation sequence$$ - -$head Syntax$$ -$icode%b% = EqualOpSeq(%x%, %y%)%$$ - -$head Purpose$$ -Determine if two $icode x$$ and $icode y$$ are identically equal; i.e., -not only is $icode%x% == %y%$$ true, but -if they are $cref/variables/glossary/Variable/$$, -they correspond have the same -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Motivation$$ -Sometimes it is useful to cache information -and only recalculate when a function's arguments change. -In the case of AD variables, -it may be important not only when the argument values are equal, -but when they are related to the -$cref/independent variables/glossary/Tape/Independent Variable/$$ -by the same operation sequence. -After the assignment -$codei% - %y% = %x% -%$$ -these two AD objects would not only have equal values, -but would also correspond to the same operation sequence. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const AD<%Base%> &%x% -%$$ - -$head y$$ -The argument $icode y$$ has prototype -$codei% - const AD<%Base%> &%y% -%$$ - -$head b$$ -The result $icode b$$ has prototype -$codei% - bool %b% -%$$ -The result is true if and only if one of the following cases holds: - -$list number$$ -Both $icode x$$ and $icode y$$ are variables -and correspond to the same operation sequence. -$lnext -Both $icode x$$ and $icode y$$ are parameters, -$icode Base$$ is an AD type, -and $codei%EqualOpSeq( Value(%x%) , Value(%y%) )%$$ is true. -$lnext -Both $icode x$$ and $icode y$$ are parameters, -$icode Base$$ is not an AD type, -and $icode%x% == %y%%$$ is true. -$lend - - -$head Example$$ -$children% - example/equal_op_seq.cpp -%$$ -The file -$cref equal_op_seq.cpp$$ -contains an example and test of $code EqualOpSeq$$. -It returns true if it succeeds and false otherwise. - - -$end ------------------------------------------------------------------------------- -*/ - - -namespace CppAD { - template - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION - bool EqualOpSeq(const AD &x, const AD &y) - { - if( Parameter(x) ) - { if( Parameter(y) ) - return EqualOpSeq(x.value_, y.value_); - else return false; - } - else if( Parameter(y) ) - return false; - - return (x.taddr_ == y.taddr_); - } - -} - -# endif diff --git a/ct_core/include/ct/external/cppad/local/erf.hpp b/ct_core/include/ct/external/cppad/local/erf.hpp deleted file mode 100644 index 14f932cde..000000000 --- a/ct_core/include/ct/external/cppad/local/erf.hpp +++ /dev/null @@ -1,107 +0,0 @@ -// $Id: erf.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_ERF_HPP -# define CPPAD_ERF_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin erf$$ -$spell - erf - const - Vec - std - cmath - CppAD - Vedder -$$ -$section The Error Function$$ - -$head Syntax$$ -$icode%y% = erf(%x%)%$$ - -$head Description$$ -Returns the value of the error function which is defined by -$latex \[ -{\rm erf} (x) = \frac{2}{ \sqrt{\pi} } \int_0^x \exp( - t * t ) \; {\bf d} t -\] $$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head CPPAD_USE_CPLUSPLUS_2011$$ - -$subhead true$$ -If this preprocessor symbol is true ($code 1$$), -and $icode x$$ is an AD type, -this is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$subhead false$$ -If this preprocessor symbol is false ($code 0$$), -CppAD uses a fast approximation (few numerical operations) -with relative error bound $latex 4 \times 10^{-4}$$; see -Vedder, J.D., -$icode Simple approximations for the error function and its inverse$$, -American Journal of Physics, -v 55, -n 8, -1987, -p 762-3. - -$head Example$$ -$children% - example/erf.cpp -%$$ -The file -$cref erf.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ -# include -# if ! CPPAD_USE_CPLUSPLUS_2011 - -// BEGIN CppAD namespace -namespace CppAD { - -template -Type erf_template(const Type &x) -{ using CppAD::exp; - const Type a = static_cast(993./880.); - const Type b = static_cast(89./880.); - - return tanh( (a + b * x * x) * x ); -} - -inline float erf(const float &x) -{ return erf_template(x); } - -inline double erf(const double &x) -{ return erf_template(x); } - -template -inline AD erf(const AD &x) -{ return erf_template(x); } - -template -inline AD erf(const VecAD_reference &x) -{ return erf_template( x.ADBase() ); } - - -} // END CppAD namespace - -# endif // CPPAD_USE_CPLUSPLUS_2011 -# endif // CPPAD_ERF_INCLUDED diff --git a/ct_core/include/ct/external/cppad/local/erf_op.hpp b/ct_core/include/ct/external/cppad/local/erf_op.hpp deleted file mode 100644 index a32ea93e9..000000000 --- a/ct_core/include/ct/external/cppad/local/erf_op.hpp +++ /dev/null @@ -1,429 +0,0 @@ -// $Id$ -# ifndef CPPAD_ERF_OP_HPP -# define CPPAD_ERF_OP_HPP -# if CPPAD_USE_CPLUSPLUS_2011 - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include -# include -# include - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file erf_op.hpp -Forward and reverse mode calculations for z = erf(x). -*/ - -/*! -Forward mode Taylor coefficient for result of op = ErfOp. - -The C++ source code corresponding to this operation is -\verbatim - z = erf(x) -\endverbatim - -\par CPPAD_HAS_ERROF_FUNCTION -This macro is either zero or one and forward_erf_op is only defined -when it is one. - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param p -lowest order of the Taylor coefficients that we are computing. - -\param q -highest order of the Taylor coefficients that we are computing. - -\param i_z -variable index corresponding to the last (primary) result for this operation; -i.e. the row index in \a taylor corresponding to z. -The auxillary result is called y has index \a i_z - 1. - -\param arg -arg[0]: is the variable index corresponding to x. -\n -arg[1]: is the parameter index corresponding to the value zero. -\n -\arg[2]: is the parameter index correspodning to the value 2 / sqrt(pi). - -\param parameter -parameter[ arg[1] ] is the value zero, -and parameter[ arg[2] ] is the value 2 / sqrt(pi). - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\param taylor -\b Input: -taylor [ arg[0] * cap_order + k ] -for k = 0 , ... , q, -is the k-th order Taylor coefficient corresponding to x. -\n -\b Input: -taylor [ i_z * cap_order + k ] -for k = 0 , ... , p - 1, -is the k-th order Taylor coefficient corresponding to z. -\n -\b Input: -taylor [ ( i_z - j) * cap_order + k ] -for k = 0 , ... , p-1, -and j = 0 , ... , 4, -is the k-th order Taylor coefficient corresponding to the j-th result for z. -\n -\b Output: -taylor [ (i_z-j) * cap_order + k ], -for k = p , ... , q, -and j = 0 , ... , 4, -is the k-th order Taylor coefficient corresponding to the j-th result for z. - -\par Checked Assertions -\li NumArg(op) == 3 -\li NumRes(op) == 5 -\li q < cap_order -\li p <= q -*/ -template -inline void forward_erf_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ErfOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ErfOp) == 5 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // array used to pass parameter values for sub-operations - addr_t addr[2]; - - // convert from final result to first result - i_z -= 4; // 4 = NumRes(ErfOp) - 1; - - // z_0 = x * x - addr[0] = arg[0]; // x - addr[1] = arg[0]; // x - forward_mulvv_op(p, q, i_z+0, addr, parameter, cap_order, taylor); - - // z_1 = - x * x - addr[0] = arg[1]; // zero - addr[1] = i_z; // z_0 - forward_subpv_op(p, q, i_z+1, addr, parameter, cap_order, taylor); - - // z_2 = exp( - x * x ) - forward_exp_op(p, q, i_z+2, i_z+1, cap_order, taylor); - - // z_3 = (2 / sqrt(pi)) * exp( - x * x ) - addr[0] = arg[2]; // 2 / sqrt(pi) - addr[1] = i_z + 2; // z_2 - forward_mulpv_op(p, q, i_z+3, addr, parameter, cap_order, taylor); - - // pointers to taylor coefficients for x , z_3, and z_4 - Base* x = taylor + arg[0] * cap_order; - Base* z_3 = taylor + (i_z+3) * cap_order; - Base* z_4 = taylor + (i_z+4) * cap_order; - - // calculte z_4 coefficients - if( p == 0 ) - { // zero order Taylor coefficient for z_4 - z_4[0] = erf(x[0]); - p++; - } - for(size_t j = p; j <= q; j++) - { Base base_j = static_cast(j); - z_4[j] = static_cast(0); - for(size_t k = 1; k <= j; k++) - z_4[j] += (Base(k) / base_j) * x[k] * z_3[j-k]; - } -} - -/*! -Zero order Forward mode Taylor coefficient for result of op = ErfOp. - -The C++ source code corresponding to this operation is -\verbatim - z = erf(x) -\endverbatim - -\par CPPAD_HAS_ERROF_FUNCTION -This macro is either zero or one and forward_erf_op is only defined -when it is one. - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param i_z -variable index corresponding to the last (primary) result for this operation; -i.e. the row index in \a taylor corresponding to z. -The auxillary result is called y has index \a i_z - 1. - -\param arg -arg[0]: is the variable index corresponding to x. -\n -arg[1]: is the parameter index corresponding to the value zero. -\n -\arg[2]: is the parameter index correspodning to the value 2 / sqrt(pi). - -\param parameter -parameter[ arg[1] ] is the value zero, -and parameter[ arg[2] ] is the value 2 / sqrt(pi). - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\param taylor -\b Input: -taylor [ arg[0] * cap_order + 0 ] -is the zero order Taylor coefficient corresponding to x. -\n -\b Input: -taylor [ i_z * cap_order + 0 ] -is the zero order Taylor coefficient corresponding to z. -\n -\b Output: -taylor [ (i_z-j) * cap_order + 0 ], -for j = 0 , ... , 4, -is the zero order Taylor coefficient for j-th result corresponding to z. - -\par Checked Assertions -\li NumArg(op) == 3 -\li NumRes(op) == 5 -\li q < cap_order -\li p <= q -*/ -template -inline void forward_erf_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ErfOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ErfOp) == 5 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // array used to pass parameter values for sub-operations - addr_t addr[2]; - - // convert from final result to first result - i_z -= 4; // 4 = NumRes(ErfOp) - 1; - - // z_0 = x * x - addr[0] = arg[0]; // x - addr[1] = arg[0]; // x - forward_mulvv_op_0(i_z+0, addr, parameter, cap_order, taylor); - - // z_1 = - x * x - addr[0] = arg[1]; // zero - addr[1] = i_z; // z_0 - forward_subpv_op_0(i_z+1, addr, parameter, cap_order, taylor); - - // z_2 = exp( - x * x ) - forward_exp_op_0(i_z+2, i_z+1, cap_order, taylor); - - // z_3 = (2 / sqrt(pi)) * exp( - x * x ) - addr[0] = arg[2]; // 2 / sqrt(pi) - addr[1] = i_z + 2; // z_2 - forward_mulpv_op_0(i_z+3, addr, parameter, cap_order, taylor); - - // zero order Taylor coefficient for z_4 - Base* x = taylor + arg[0] * cap_order; - Base* z_4 = taylor + (i_z + 4) * cap_order; - z_4[0] = erf(x[0]); -} - -/*! -Compute reverse mode partial derivatives for result of op = ErfOp. - -The C++ source code corresponding to this operation is -\verbatim - z = erf(x) -\endverbatim - -\par CPPAD_HAS_ERROF_FUNCTION -This macro is either zero or one and reverse_tan_op is only defined -when it is one. - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param d -highest order Taylor of the Taylor coefficients that we are computing -the partial derivatives with respect to. - -\param i_z -variable index corresponding to the last (primary) result for this operation; -i.e. the row index in \a taylor corresponding to z. -The auxillary result is called y has index \a i_z - 1. - -\param arg -arg[0]: is the variable index corresponding to x. -\n -arg[1]: is the parameter index corresponding to the value zero. -\n -\arg[2]: is the parameter index correspodning to the value 2 / sqrt(pi). - -\param parameter -parameter[ arg[1] ] is the value zero, -and parameter[ arg[2] ] is the value 2 / sqrt(pi). - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\param taylor -\b Input: -taylor [ arg[0] * cap_order + k ] -for k = 0 , ... , d, -is the k-th order Taylor coefficient corresponding to x. -\n -taylor [ (i_z - j) * cap_order + k ] -for k = 0 , ... , d, -and for j = 0 , ... , 4, -is the k-th order Taylor coefficient corresponding to the j-th result -for this operation. - -\param nc_partial -number of columns in the matrix containing all the partial derivatives - -\param partial -\b Input: -partial [ arg[0] * nc_partial + k ] -for k = 0 , ... , d, -is the partial derivative of G( z , x , w , u , ... ) with respect to -the k-th order Taylor coefficient for x. -\n -\b Input: -partial [ (i_z - j) * nc_partial + k ] -for k = 0 , ... , d, -and for j = 0 , ... , 4, -is the partial derivative of G( z , x , w , u , ... ) with respect to -the k-th order Taylor coefficient for the j-th result of this operation. -\n -\b Output: -partial [ arg[0] * nc_partial + k ] -for k = 0 , ... , d, -is the partial derivative of H( x , w , u , ... ) with respect to -the k-th order Taylor coefficient for x. -\n -\b Output: -partial [ (i_z-j) * nc_partial + k ] -for k = 0 , ... , d, -and for j = 0 , ... , 4, -may be used as work space; i.e., may change in an unspecified manner. - -\par Checked Assertions -\li NumArg(op) == 3 -\li NumRes(op) == 5 -\li q < cap_order -\li p <= q -*/ -template -inline void reverse_erf_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ErfOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ErfOp) == 5 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - - // array used to pass parameter values for sub-operations - addr_t addr[2]; - - // If pz is zero, make sure this operation has no effect - // (zero times infinity or nan would be non-zero). - Base* pz = partial + i_z * nc_partial; - bool skip(true); - for(size_t i_d = 0; i_d <= d; i_d++) - skip &= IdenticalZero(pz[i_d]); - if( skip ) - return; - - // convert from final result to first result - i_z -= 4; // 4 = NumRes(ErfOp) - 1; - - // Taylor coefficients and partials corresponding to x - const Base* x = taylor + arg[0] * cap_order; - Base* px = partial + arg[0] * nc_partial; - - // Taylor coefficients and partials corresponding to z_3 - const Base* z_3 = taylor + (i_z+3) * cap_order; - Base* pz_3 = partial + (i_z+3) * nc_partial; - - // Taylor coefficients and partials corresponding to z_4 - Base* pz_4 = partial + (i_z+4) * nc_partial; - - // Reverse z_4 - size_t j = d; - while(j) - { pz_4[j] /= Base(j); - for(size_t k = 1; k <= j; k++) - { px[k] += azmul(pz_4[j], z_3[j-k]) * Base(k); - pz_3[j-k] += azmul(pz_4[j], x[k]) * Base(k); - } - j--; - } - px[0] += azmul(pz_4[0], z_3[0]); - - // z_3 = (2 / sqrt(pi)) * exp( - x * x ) - addr[0] = arg[2]; // 2 / sqrt(pi) - addr[1] = i_z + 2; // z_2 - reverse_mulpv_op( - d, i_z+3, addr, parameter, cap_order, taylor, nc_partial, partial - ); - - // z_2 = exp( - x * x ) - reverse_exp_op( - d, i_z+2, i_z+1, cap_order, taylor, nc_partial, partial - ); - - // z_1 = - x * x - addr[0] = arg[1]; // zero - addr[1] = i_z; // z_0 - reverse_subpv_op( - d, i_z+1, addr, parameter, cap_order, taylor, nc_partial, partial - ); - - // z_0 = x * x - addr[0] = arg[0]; // x - addr[1] = arg[0]; // x - reverse_mulvv_op( - d, i_z+0, addr, parameter, cap_order, taylor, nc_partial, partial - ); - -} - - -} // END_CPPAD_NAMESPACE -# endif // CPPAD_USE_CPLUSPLUS_2011 -# endif // CPPAD_ERF_OP_INCLUDED diff --git a/ct_core/include/ct/external/cppad/local/exp_op.hpp b/ct_core/include/ct/external/cppad/local/exp_op.hpp deleted file mode 100644 index 922c6c0fa..000000000 --- a/ct_core/include/ct/external/cppad/local/exp_op.hpp +++ /dev/null @@ -1,195 +0,0 @@ -// $Id: exp_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_EXP_OP_HPP -# define CPPAD_EXP_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file exp_op.hpp -Forward and reverse mode calculations for z = exp(x). -*/ - - -/*! -Forward mode Taylor coefficient for result of op = ExpOp. - -The C++ source code corresponding to this operation is -\verbatim - z = exp(x) -\endverbatim - -\copydetails forward_unary1_op -*/ -template -inline void forward_exp_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ExpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ExpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - - size_t k; - if( p == 0 ) - { z[0] = exp( x[0] ); - p++; - } - for(size_t j = p; j <= q; j++) - { - z[j] = x[1] * z[j-1]; - for(k = 2; k <= j; k++) - z[j] += Base(k) * x[k] * z[j-k]; - z[j] /= Base(j); - } -} - - -/*! -Multiple direction forward mode Taylor coefficient for op = ExpOp. - -The C++ source code corresponding to this operation is -\verbatim - z = exp(x) -\endverbatim - -\copydetails forward_unary1_op_dir -*/ -template -inline void forward_exp_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ExpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ExpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - - size_t m = (q-1)*r + 1; - for(size_t ell = 0; ell < r; ell++) - { z[m+ell] = Base(q) * x[m+ell] * z[0]; - for(size_t k = 1; k < q; k++) - z[m+ell] += Base(k) * x[(k-1)*r+ell+1] * z[(q-k-1)*r+ell+1]; - z[m+ell] /= Base(q); - } -} - -/*! -Zero order forward mode Taylor coefficient for result of op = ExpOp. - -The C++ source code corresponding to this operation is -\verbatim - z = exp(x) -\endverbatim - -\copydetails forward_unary1_op_0 -*/ -template -inline void forward_exp_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ExpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ExpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = exp( x[0] ); -} -/*! -Reverse mode partial derivatives for result of op = ExpOp. - -The C++ source code corresponding to this operation is -\verbatim - z = exp(x) -\endverbatim - -\copydetails reverse_unary1_op -*/ - -template -inline void reverse_exp_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ExpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ExpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to result - const Base* z = taylor + i_z * cap_order; - Base* pz = partial + i_z * nc_partial; - - // If pz is zero, make sure this operation has no effect - // (zero times infinity or nan would be non-zero). - bool skip(true); - for(size_t i_d = 0; i_d <= d; i_d++) - skip &= IdenticalZero(pz[i_d]); - if( skip ) - return; - - // loop through orders in reverse - size_t j, k; - j = d; - while(j) - { // scale partial w.r.t z[j] - pz[j] /= Base(j); - - for(k = 1; k <= j; k++) - { px[k] += Base(k) * azmul(pz[j], z[j-k]); - pz[j-k] += Base(k) * azmul(pz[j], x[k]); - } - --j; - } - px[0] += azmul(pz[0], z[0]); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/expm1.hpp b/ct_core/include/ct/external/cppad/local/expm1.hpp deleted file mode 100644 index a88c604f7..000000000 --- a/ct_core/include/ct/external/cppad/local/expm1.hpp +++ /dev/null @@ -1,97 +0,0 @@ -// $Id$ -# ifndef CPPAD_EXPM1_HPP -# define CPPAD_EXPM1_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin expm1$$ -$spell - exp - expm1 - const - Vec - std - cmath - CppAD -$$ -$section The Exponential Function Minus One: expm1$$ - -$head Syntax$$ -$icode%y% = expm1(%x%)%$$ - -$head Description$$ -Returns the value of the exponential function minus one which is defined -by $icode%y% == exp(%x%) - 1%$$. - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head CPPAD_USE_CPLUSPLUS_2011$$ - -$subhead true$$ -If this preprocessor symbol is true ($code 1$$), -and $icode x$$ is an AD type, -this is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$subhead false$$ -If this preprocessor symbol is false ($code 0$$), -CppAD uses the representation -$latex \[ -\R{expm1} (x) = \exp(x) - 1 -\] $$ -to compute this function. - -$head Example$$ -$children% - example/expm1.cpp -%$$ -The file -$cref expm1.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ -# include -# if ! CPPAD_USE_CPLUSPLUS_2011 - -// BEGIN CppAD namespace -namespace CppAD { - -template -Type expm1_template(const Type &x) -{ return CppAD::exp(x) - Type(1); -} - -inline float expm1(const float &x) -{ return expm1_template(x); } - -inline double expm1(const double &x) -{ return expm1_template(x); } - -template -inline AD expm1(const AD &x) -{ return expm1_template(x); } - -template -inline AD expm1(const VecAD_reference &x) -{ return expm1_template( x.ADBase() ); } - - -} // END CppAD namespace - -# endif // CPPAD_USE_CPLUSPLUS_2011 -# endif // CPPAD_EXPM1_INCLUDED diff --git a/ct_core/include/ct/external/cppad/local/expm1_op.hpp b/ct_core/include/ct/external/cppad/local/expm1_op.hpp deleted file mode 100644 index 2e4d54ea5..000000000 --- a/ct_core/include/ct/external/cppad/local/expm1_op.hpp +++ /dev/null @@ -1,201 +0,0 @@ -// $Id$ -# ifndef CPPAD_EXPM1_OP_HPP -# define CPPAD_EXPM1_OP_HPP -# if CPPAD_USE_CPLUSPLUS_2011 - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file expm1_op.hpp -Forward and reverse mode calculations for z = expm1(x). -*/ - - -/*! -Forward mode Taylor coefficient for result of op = Expm1Op. - -The C++ source code corresponding to this operation is -\verbatim - z = expm1(x) -\endverbatim - -\copydetails forward_unary1_op -*/ -template -inline void forward_expm1_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(Expm1Op) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(Expm1Op) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - - size_t k; - if( p == 0 ) - { z[0] = expm1( x[0] ); - p++; - } - for(size_t j = p; j <= q; j++) - { - z[j] = x[1] * z[j-1]; - for(k = 2; k <= j; k++) - z[j] += Base(k) * x[k] * z[j-k]; - z[j] /= Base(j); - z[j] += x[j]; - } -} - - -/*! -Multiple direction forward mode Taylor coefficient for op = Expm1Op. - -The C++ source code corresponding to this operation is -\verbatim - z = expm1(x) -\endverbatim - -\copydetails forward_unary1_op_dir -*/ -template -inline void forward_expm1_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(Expm1Op) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(Expm1Op) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - - size_t m = (q-1)*r + 1; - for(size_t ell = 0; ell < r; ell++) - { z[m+ell] = Base(q) * x[m+ell] * z[0]; - for(size_t k = 1; k < q; k++) - z[m+ell] += Base(k) * x[(k-1)*r+ell+1] * z[(q-k-1)*r+ell+1]; - z[m+ell] /= Base(q); - z[m+ell] += x[m+ell]; - } -} - -/*! -Zero order forward mode Taylor coefficient for result of op = Expm1Op. - -The C++ source code corresponding to this operation is -\verbatim - z = expm1(x) -\endverbatim - -\copydetails forward_unary1_op_0 -*/ -template -inline void forward_expm1_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(Expm1Op) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(Expm1Op) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = expm1( x[0] ); -} -/*! -Reverse mode partial derivatives for result of op = Expm1Op. - -The C++ source code corresponding to this operation is -\verbatim - z = expm1(x) -\endverbatim - -\copydetails reverse_unary1_op -*/ - -template -inline void reverse_expm1_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(Expm1Op) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(Expm1Op) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to result - const Base* z = taylor + i_z * cap_order; - Base* pz = partial + i_z * nc_partial; - - // If pz is zero, make sure this operation has no effect - // (zero times infinity or nan would be non-zero). - bool skip(true); - for(size_t i_d = 0; i_d <= d; i_d++) - skip &= IdenticalZero(pz[i_d]); - if( skip ) - return; - - // loop through orders in reverse - size_t j, k; - j = d; - while(j) - { px[j] += pz[j]; - - // scale partial w.r.t z[j] - pz[j] /= Base(j); - - for(k = 1; k <= j; k++) - { px[k] += Base(k) * azmul(pz[j], z[j-k]); - pz[j-k] += Base(k) * azmul(pz[j], x[k]); - } - --j; - } - px[0] += pz[0] + azmul(pz[0], z[0]); -} - -} // END_CPPAD_NAMESPACE -# endif -# endif diff --git a/ct_core/include/ct/external/cppad/local/for_hes_sweep.hpp b/ct_core/include/ct/external/cppad/local/for_hes_sweep.hpp deleted file mode 100644 index c8a4f48a7..000000000 --- a/ct_core/include/ct/external/cppad/local/for_hes_sweep.hpp +++ /dev/null @@ -1,607 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_FOR_HES_SWEEP_HPP -# define CPPAD_LOCAL_FOR_HES_SWEEP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { namespace local { // BEGIN_CPPAD_LOCAL_NAMESPACE -/*! -\file for_hes_sweep.hpp -Compute Forward mode Hessian sparsity patterns. -*/ - -/*! -\def CPPAD_FOR_HES_SWEEP_TRACE -This value is either zero or one. -Zero is the normal operational value. -If it is one, a trace of every rev_hes_sweep computation is printed. -*/ -# define CPPAD_FOR_HES_SWEEP_TRACE 0 - -/*! -Given the forward Jacobian sparsity pattern for all the variables, -and the reverse Jacobian sparsity pattern for the dependent variables, -ForHesSweep computes the Hessian sparsity pattern for all the independent -variables. - -\tparam Base -base type for the operator; i.e., this operation sequence was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\tparam Vector_set -is the type used for vectors of sets. It can be either -sparse_pack or sparse_list. - -\param n -is the number of independent variables on the tape. - -\param numvar -is the total number of variables on the tape; i.e., -\a play->num_var_rec(). -This is also the number of rows in the entire sparsity pattern -\a for_hes_sparse. - -\param play -The information stored in \a play -is a recording of the operations corresponding to a function -\f[ - F : {\bf R}^n \rightarrow {\bf R}^m -\f] -where \f$ n \f$ is the number of independent variables -and \f$ m \f$ is the number of dependent variables. -The object \a play is effectly constant. -It is not declared const because while playing back the tape -the object \a play holds information about the current location -with in the tape and this changes during playback. - -\param for_jac_sparse -For i = 0 , ... , \a numvar - 1, -(for all the variables on the tape), -the forward Jacobian sparsity pattern for the variable with index i -corresponds to the set with index i in \a for_jac_sparse. - -\param rev_jac_sparse -\b Input: -For i = 0, ... , \a numvar - 1 -the if the function we are computing the Hessian for has a non-zero -derivative w.r.t. variable with index i, -the set with index i has element zero. -Otherwise it has no elements. - -\param for_hes_sparse -The reverse Hessian sparsity pattern for the variable with index i -corresponds to the set with index i in \a for_hes_sparse. -The number of rows in this sparsity patter is n+1 and the row -with index zero is not used. -\n -\n -\b Input: For i = 1 , ... , \a n -the reverse Hessian sparsity pattern for the variable with index i is empty. -\n -\n -\b Output: For j = 1 , ... , \a n, -the reverse Hessian sparsity pattern for the independent dependent variable -with index (j-1) is given by the set with index j -in \a for_hes_sparse. -*/ - -template -void ForHesSweep( - size_t n, - size_t numvar, - local::player* play, - const Vector_set& for_jac_sparse, - const Vector_set& rev_jac_sparse, - Vector_set& for_hes_sparse -) -{ - OpCode op; - size_t i_op; - size_t i_var; - - const addr_t* arg = CPPAD_NULL; - - // length of the parameter vector (used by CppAD assert macros) - const size_t num_par = play->num_par_rec(); - - size_t i, j, k; - - // check numvar argument - size_t limit = n+1; - CPPAD_ASSERT_UNKNOWN( play->num_var_rec() == numvar ); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse.n_set() == numvar ); - CPPAD_ASSERT_UNKNOWN( for_hes_sparse.n_set() == limit ); - CPPAD_ASSERT_UNKNOWN( numvar > 0 ); - - // upper limit exclusive for set elements - CPPAD_ASSERT_UNKNOWN( for_jac_sparse.end() == limit ); - CPPAD_ASSERT_UNKNOWN( for_hes_sparse.end() == limit ); - - // vecad_sparsity contains a sparsity pattern for each VecAD object. - // vecad_ind maps a VecAD index (beginning of the VecAD object) - // to the index for the corresponding set in vecad_sparsity. - size_t num_vecad_ind = play->num_vec_ind_rec(); - size_t num_vecad_vec = play->num_vecad_vec_rec(); - Vector_set vecad_sparse; - vecad_sparse.resize(num_vecad_vec, limit); - pod_vector vecad_ind; - pod_vector vecad_jac; - if( num_vecad_vec > 0 ) - { size_t length; - vecad_ind.extend(num_vecad_ind); - vecad_jac.extend(num_vecad_vec); - j = 0; - for(i = 0; i < num_vecad_vec; i++) - { // length of this VecAD - length = play->GetVecInd(j); - // set vecad_ind to proper index for this VecAD - vecad_ind[j] = i; - // make all other values for this vector invalid - for(k = 1; k <= length; k++) - vecad_ind[j+k] = num_vecad_vec; - // start of next VecAD - j += length + 1; - // initialize this vector's reverse jacobian value - vecad_jac[i] = false; - } - CPPAD_ASSERT_UNKNOWN( j == play->num_vec_ind_rec() ); - } - - // work space used by UserOp. - vector user_ix; // variable indices for argument vector x - vector user_x; // parameters in x as integers - // - // - typedef std::set size_set; - vector< size_set > set_h; // forward Hessian sparsity - vector bool_h; // forward Hessian sparsity - vectorBool pack_h; // forward Hessian sparstiy - // - vector user_vx; // which components of x are variables - vector user_r; // forward Jacobian sparsity for x - vector user_s; // reverse Jacobian sparsity for y - // - // information defined by forward_user - size_t user_old=0, user_m=0, user_n=0, user_i=0, user_j=0; - enum_user_state user_state = start_user; // proper initialization - // - atomic_base* user_atom = CPPAD_NULL; // user's atomic op calculator - bool user_pack = false; // sparsity pattern type is pack - bool user_bool = false; // sparsity pattern type is bool - bool user_set = false; // sparsity pattern type is set - bool user_ok = false; // atomic op return value - // - // pointer to the beginning of the parameter vector - // (used by user atomic functions) - const Base* parameter = CPPAD_NULL; - if( num_par > 0 ) - parameter = play->GetPar(); - - // Initialize - play->forward_start(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( op == BeginOp ); - bool more_operators = true; -# if CPPAD_FOR_HES_SWEEP_TRACE - std::cout << std::endl; - CppAD::vectorBool zf_value(limit); - CppAD::vectorBool zh_value(limit * limit); -# endif - bool flag; // temporary for use in switch cases below - while(more_operators) - { - // next op - play->forward_next(op, arg, i_op, i_var); -# ifndef NDEBUG - if( i_op <= n ) - { CPPAD_ASSERT_UNKNOWN((op == InvOp) | (op == BeginOp)); - } - else CPPAD_ASSERT_UNKNOWN((op != InvOp) & (op != BeginOp)); -# endif - - // does the Hessian in question have a non-zero derivative - // with respect to this variable - bool include = rev_jac_sparse.is_element(i_var, 0); - // - // operators to include even if derivative is zero - include |= op == EndOp; - include |= op == CSkipOp; - include |= op == CSumOp; - include |= op == UserOp; - include |= op == UsrapOp; - include |= op == UsravOp; - include |= op == UsrrpOp; - include |= op == UsrrvOp; - // - if( include ) switch( op ) - { // operators that should not occurr - // case BeginOp - // ------------------------------------------------- - - // operators that do not affect hessian - case AbsOp: - case AddvvOp: - case AddpvOp: - case CExpOp: - case DisOp: - case DivvpOp: - case InvOp: - case LdpOp: - case LdvOp: - case MulpvOp: - case ParOp: - case PriOp: - case SignOp: - case StppOp: - case StpvOp: - case StvpOp: - case StvvOp: - case SubvvOp: - case SubpvOp: - case SubvpOp: - case ZmulpvOp: - case ZmulvpOp: - break; - // ------------------------------------------------- - - // nonlinear unary operators - case AcosOp: - case AsinOp: - case AtanOp: - case CosOp: - case CoshOp: - case ExpOp: - case LogOp: - case SinOp: - case SinhOp: - case SqrtOp: - case TanOp: - case TanhOp: -# if CPPAD_USE_CPLUSPLUS_2011 - case AcoshOp: - case AsinhOp: - case AtanhOp: - case Expm1Op: - case Log1pOp: -# endif - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ) - forward_sparse_hessian_nonlinear_unary_op( - arg[0], for_jac_sparse, for_hes_sparse - ); - break; - // ------------------------------------------------- - - case CSkipOp: - // CSkipOp has a variable number of arguments and - // reverse_next thinks it one has one argument. - // We must inform reverse_next of this special case. - play->forward_cskip(op, arg, i_op, i_var); - break; - // ------------------------------------------------- - - case CSumOp: - // CSumOp has a variable number of arguments and - // reverse_next thinks it one has one argument. - // We must inform reverse_next of this special case. - play->forward_csum(op, arg, i_op, i_var); - break; - // ------------------------------------------------- - - case DivvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - forward_sparse_hessian_div_op( - arg, for_jac_sparse, for_hes_sparse - ); - break; - // ------------------------------------------------- - - case DivpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - forward_sparse_hessian_nonlinear_unary_op( - arg[1], for_jac_sparse, for_hes_sparse - ); - break; - // ------------------------------------------------- - - case EndOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 0); - more_operators = false; - break; - // ------------------------------------------------- - - case ErfOp: - // arg[1] is always the parameter 0 - // arg[2] is always the parameter 2 / sqrt(pi) - CPPAD_ASSERT_NARG_NRES(op, 3, 5); - forward_sparse_hessian_nonlinear_unary_op( - arg[0], for_jac_sparse, for_hes_sparse - ); - break; - // ------------------------------------------------- - - // ------------------------------------------------- - // logical comparision operators - case EqpvOp: - case EqvvOp: - case LtpvOp: - case LtvpOp: - case LtvvOp: - case LepvOp: - case LevpOp: - case LevvOp: - case NepvOp: - case NevvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 0); - break; - // ------------------------------------------------- - - case MulvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - forward_sparse_hessian_mul_op( - arg, for_jac_sparse, for_hes_sparse - ); - break; - // ------------------------------------------------- - - case PowpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 3) - forward_sparse_hessian_nonlinear_unary_op( - arg[1], for_jac_sparse, for_hes_sparse - ); - break; - // ------------------------------------------------- - - case PowvpOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 3) - forward_sparse_hessian_nonlinear_unary_op( - arg[0], for_jac_sparse, for_hes_sparse - ); - break; - // ------------------------------------------------- - - case PowvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 3) - forward_sparse_hessian_pow_op( - arg, for_jac_sparse, for_hes_sparse - ); - break; - // ------------------------------------------------- - - case UserOp: - // start or end an atomic operation sequence - flag = user_state == start_user; - user_atom = play->forward_user(op, user_state, - user_old, user_m, user_n, user_i, user_j - ); - if( flag ) - { user_x.resize( user_n ); - // - user_pack = user_atom->sparsity() == - atomic_base::pack_sparsity_enum; - user_bool = user_atom->sparsity() == - atomic_base::bool_sparsity_enum; - user_set = user_atom->sparsity() == - atomic_base::set_sparsity_enum; - CPPAD_ASSERT_UNKNOWN( user_pack || user_bool || user_set ); - user_ix.resize(user_n); - user_vx.resize(user_n); - user_r.resize(user_n); - user_s.resize(user_m); - - // simpler to initialize sparsity patterns as empty - for(i = 0; i < user_m; i++) - user_s[i] = false; - for(i = 0; i < user_n; i++) - user_r[i] = false; - if( user_pack ) - { pack_h.resize(user_n * user_n); - for(i = 0; i < user_n; i++) - { for(j = 0; j < user_n; j++) - pack_h[ i * user_n + j] = false; - } - } - if( user_bool ) - { bool_h.resize(user_n * user_n); - for(i = 0; i < user_n; i++) - { for(j = 0; j < user_n; j++) - bool_h[ i * user_n + j] = false; - } - } - if( user_set ) - { set_h.resize(user_n); - for(i = 0; i < user_n; i++) - set_h[i].clear(); - } - } - else - { // call users function for this operation - user_atom->set_old(user_old); - if( user_pack ) - { user_ok = user_atom->for_sparse_hes( - user_vx, user_r, user_s, pack_h, user_x - ); - if( ! user_ok ) user_ok = user_atom->for_sparse_hes( - user_vx, user_r, user_s, pack_h - ); - } - if( user_bool ) - { user_ok = user_atom->for_sparse_hes( - user_vx, user_r, user_s, bool_h, user_x - ); - if( ! user_ok ) user_ok = user_atom->for_sparse_hes( - user_vx, user_r, user_s, bool_h - ); - } - if( user_set ) - { user_ok = user_atom->for_sparse_hes( - user_vx, user_r, user_s, set_h, user_x - ); - if( ! user_ok ) user_ok = user_atom->for_sparse_hes( - user_vx, user_r, user_s, set_h - ); - } - if( ! user_ok ) - { std::string msg = - user_atom->afun_name() - + ": atomic_base.for_sparse_hes: returned false\n"; - if( user_pack ) - msg += "sparsity = pack_sparsity_enum"; - if( user_bool ) - msg += "sparsity = bool_sparsity_enum"; - if( user_set ) - msg += "sparsity = set_sparsity_enum"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } - for(i = 0; i < user_n; i++) for(j = 0; j < user_n; j++) - { if( user_ix[i] > 0 && user_ix[j] > 0 ) - { flag = false; - if( user_pack ) - flag = pack_h[i * user_n + j]; - if( user_bool ) - flag = bool_h[i * user_n + j]; - if( user_set ) - flag = set_h[i].find(j) != set_h[i].end(); - if( flag ) - { size_t i_x = user_ix[i]; - size_t j_x = user_ix[j]; - for_hes_sparse.binary_union( - i_x, i_x, j_x, for_jac_sparse - ); - for_hes_sparse.binary_union( - j_x, j_x, i_x, for_jac_sparse - ); - } - } - } - } - break; - - case UsrapOp: - // parameter argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - user_ix[user_j] = 0; - user_vx[user_j] = false; - // - // parameters as integers - user_x[user_j] = parameter[arg[0]]; - // - play->forward_user(op, user_state, - user_old, user_m, user_n, user_i, user_j - ); - break; - - case UsravOp: - // variable argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) <= i_var ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - user_ix[user_j] = arg[0]; - user_vx[user_j] = true; - // variables as integers - user_x[user_j] = CppAD::numeric_limits::quiet_NaN(); - // - { typename Vector_set::const_iterator - itr_1(for_jac_sparse, arg[0]); - i = *itr_1; - if( i < for_jac_sparse.end() ) - user_r[user_j] = true; - } - play->forward_user(op, user_state, - user_old, user_m, user_n, user_i, user_j - ); - break; - - case UsrrpOp: - // parameter result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - play->forward_user(op, user_state, - user_old, user_m, user_n, user_i, user_j - ); - break; - - case UsrrvOp: - // variable result in an atomic operation sequence - if( rev_jac_sparse.is_element(i_var, 0) ) - user_s[user_i] = true; - play->forward_user(op, user_state, - user_old, user_m, user_n, user_i, user_j - ); - break; - // ------------------------------------------------- - - case ZmulvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - forward_sparse_hessian_mul_op( - arg, for_jac_sparse, for_hes_sparse - ); - break; - - // ------------------------------------------------- - - default: - CPPAD_ASSERT_UNKNOWN(0); - } -# if CPPAD_FOR_HES_SWEEP_TRACE - if( include ) - { for(i = 0; i < limit; i++) - { zf_value[i] = false; - for(j = 0; j < limit; j++) - zh_value[i * limit + j] = false; - } - typename Vector_set::const_iterator itr_2(for_jac_sparse, i_var); - j = *itr_2; - while( j < limit ) - { zf_value[j] = true; - j = *(++itr_2); - } - for(i = 0; i < limit; i++) - { typename Vector_set::const_iterator itr_3(for_hes_sparse, i); - j = *itr_3; - while( j < limit ) - { zh_value[i * limit + j] = true; - j = *(++itr_3); - } - } - printOp( - std::cout, - play, - i_op, - i_var, - op, - arg - ); - // should also print RevJac[i_var], but printOpResult does not - // yet allow for this - if( NumRes(op) > 0 && op != BeginOp ) printOpResult( - std::cout, - 1, - &zf_value, - 1, - &zh_value - ); - std::cout << std::endl; - } - } - std::cout << std::endl; -# else - } -# endif - // value corresponding to EndOp - CPPAD_ASSERT_UNKNOWN( i_var + 1 == play->num_var_rec() ); - - return; -} -} } // END_CPPAD_LOCAL_NAMESPACE - -// preprocessor symbols that are local to this file -# undef CPPAD_FOR_HES_SWEEP_TRACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/for_jac_sweep.hpp b/ct_core/include/ct/external/cppad/local/for_jac_sweep.hpp deleted file mode 100644 index d684201d8..000000000 --- a/ct_core/include/ct/external/cppad/local/for_jac_sweep.hpp +++ /dev/null @@ -1,897 +0,0 @@ -// $Id: for_jac_sweep.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_FOR_JAC_SWEEP_HPP -# define CPPAD_FOR_JAC_SWEEP_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file for_jac_sweep.hpp -Compute Forward mode Jacobian sparsity patterns. -*/ - -/*! -\def CPPAD_FOR_JAC_SWEEP_TRACE -This value is either zero or one. -Zero is the normal operational value. -If it is one, a trace of every for_jac_sweep computation is printed. -*/ -# define CPPAD_FOR_JAC_SWEEP_TRACE 0 - -/* -\def CPPAD_ATOMIC_CALL -This avoids warnings when NDEBUG is defined and user_ok is not used. -If \c NDEBUG is defined, this resolves to -\code - user_atom->for_sparse_jac -\endcode -otherwise, it respolves to -\code - user_ok = user_atom->for_sparse_jac -\endcode -This maco is undefined at the end of this file to facillitate is -use with a different definition in other files. -*/ -# ifdef NDEBUG -# define CPPAD_ATOMIC_CALL user_atom->for_sparse_jac -# else -# define CPPAD_ATOMIC_CALL user_ok = user_atom->for_sparse_jac -# endif - -/*! -Given the sparsity pattern for the independent variables, -ForJacSweep computes the sparsity pattern for all the other variables. - -\tparam Base -base type for the operator; i.e., this operation sequence was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param dependency -Are the derivatives with respect to left and right of the expression below -considered to be non-zero: -\code - CondExpRel(left, right, if_true, if_false) -\endcode -This is used by the optimizer to obtain the correct dependency relations. - -\param n -is the number of independent variables on the tape. - -\param numvar -is the total number of variables on the tape; i.e., -\a play->num_var_rec(). - -\param play -The information stored in \a play -is a recording of the operations corresponding to a function -\f[ - F : {\bf R}^n \rightarrow {\bf R}^m -\f] -where \f$ n \f$ is the number of independent variables -and \f$ m \f$ is the number of dependent variables. -The object \a play is effectly constant. -It is not declared const because while playing back the tape -the object \a play holds information about the currentl location -with in the tape and this changes during playback. - -\param var_sparsity -\b Input: For j = 1 , ... , \a n, -the sparsity pattern for the independent variable with index (j-1) -corresponds to the set with index j in \a var_sparsity. -\n -\n -\b Output: For i = \a n + 1 , ... , \a numvar - 1, -the sparsity pattern for the variable with index i on the tape -corresponds to the set with index i in \a var_sparsity. - -\par Checked Assertions: -\li numvar == var_sparsity.n_set() -\li numvar == play->num_var_rec() -*/ - -template -void ForJacSweep( - bool dependency , - size_t n , - size_t numvar , - player* play , - Vector_set& var_sparsity ) -{ - OpCode op; - size_t i_op; - size_t i_var; - - const addr_t* arg = CPPAD_NULL; - - size_t i, j, k; - - // check numvar argument - CPPAD_ASSERT_UNKNOWN( play->num_var_rec() == numvar ); - CPPAD_ASSERT_UNKNOWN( var_sparsity.n_set() == numvar ); - - // length of the parameter vector (used by CppAD assert macros) - const size_t num_par = play->num_par_rec(); - - // cum_sparsity accumulates sparsity pattern a cummulative sum - size_t limit = var_sparsity.end(); - - // vecad_sparsity contains a sparsity pattern from each VecAD object - // to all the other variables. - // vecad_ind maps a VecAD index (the beginning of the - // VecAD object) to its from index in vecad_sparsity - size_t num_vecad_ind = play->num_vec_ind_rec(); - size_t num_vecad_vec = play->num_vecad_vec_rec(); - Vector_set vecad_sparsity; - vecad_sparsity.resize(num_vecad_vec, limit); - pod_vector vecad_ind; - if( num_vecad_vec > 0 ) - { size_t length; - vecad_ind.extend(num_vecad_ind); - j = 0; - for(i = 0; i < num_vecad_vec; i++) - { // length of this VecAD - length = play->GetVecInd(j); - // set to proper index for this VecAD - vecad_ind[j] = i; - for(k = 1; k <= length; k++) - vecad_ind[j+k] = num_vecad_vec; // invalid index - // start of next VecAD - j += length + 1; - } - CPPAD_ASSERT_UNKNOWN( j == play->num_vec_ind_rec() ); - } - - // -------------------------------------------------------------- - // work space used by UserOp. - // - typedef std::set size_set; - size_set::iterator set_itr; // iterator for a standard set - size_set::iterator set_end; // end of iterator sequence - vector< size_set > set_r; // set sparsity pattern for the argument x - vector< size_set > set_s; // set sparisty pattern for the result y - // - vector bool_r; // bool sparsity pattern for the argument x - vector bool_s; // bool sparisty pattern for the result y - // - vectorBool pack_r; // pack sparsity pattern for the argument x - vectorBool pack_s; // pack sparisty pattern for the result y - // - const size_t user_q = limit; // maximum element plus one - size_t user_index = 0; // indentifier for this atomic operation - size_t user_id = 0; // user identifier for this call to operator - size_t user_i = 0; // index in result vector - size_t user_j = 0; // index in argument vector - size_t user_m = 0; // size of result vector - size_t user_n = 0; // size of arugment vector - // - atomic_base* user_atom = CPPAD_NULL; // user's atomic op calculator - bool user_pack = false; // sparsity pattern type is pack - bool user_bool = false; // sparsity pattern type is bool - bool user_set = false; // sparsity pattern type is set -# ifndef NDEBUG - bool user_ok = false; // atomic op return value -# endif - // - // next expected operator in a UserOp sequence - enum { user_start, user_arg, user_ret, user_end } user_state = user_start; - // -------------------------------------------------------------- - -# if CPPAD_FOR_JAC_SWEEP_TRACE - std::cout << std::endl; - CppAD::vectorBool z_value(limit); -# endif - - // skip the BeginOp at the beginning of the recording - play->forward_start(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( op == BeginOp ); - bool more_operators = true; - while(more_operators) - { - // this op - play->forward_next(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( (i_op > n) | (op == InvOp) ); - CPPAD_ASSERT_UNKNOWN( (i_op <= n) | (op != InvOp) ); - CPPAD_ASSERT_ARG_BEFORE_RESULT(op, arg, i_var); - - // rest of information depends on the case - switch( op ) - { - case AbsOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case AddvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - forward_sparse_jacobian_binary_op( - i_var, arg, var_sparsity - ); - break; - // ------------------------------------------------- - - case AddpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - forward_sparse_jacobian_unary_op( - i_var, arg[1], var_sparsity - ); - break; - // ------------------------------------------------- - - case AcosOp: - // sqrt(1 - x * x), acos(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AcoshOp: - // sqrt(x * x - 1), acosh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; -# endif - // ------------------------------------------------- - - case AsinOp: - // sqrt(1 - x * x), asin(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AsinhOp: - // sqrt(1 + x * x), asinh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; -# endif - // ------------------------------------------------- - - case AtanOp: - // 1 + x * x, atan(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AtanhOp: - // 1 - x * x, atanh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; -# endif - // ------------------------------------------------- - - case CSkipOp: - // CSipOp has a variable number of arguments and - // forward_next thinks it has no arguments. - // we must inform forward_next of this special case. - play->forward_cskip(op, arg, i_op, i_var); - break; - // ------------------------------------------------- - - case CSumOp: - // CSumOp has a variable number of arguments and - // forward_next thinks it has no arguments. - // we must inform forward_next of this special case. - forward_sparse_jacobian_csum_op( - i_var, arg, var_sparsity - ); - play->forward_csum(op, arg, i_op, i_var); - break; - // ------------------------------------------------- - - case CExpOp: - forward_sparse_jacobian_cond_op( - dependency, i_var, arg, num_par, var_sparsity - ); - break; - // -------------------------------------------------- - - case CosOp: - // sin(x), cos(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // --------------------------------------------------- - - case CoshOp: - // sinh(x), cosh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case DisOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - // derivative is identically zero but dependency is not - if( dependency ) forward_sparse_jacobian_unary_op( - i_var, arg[1], var_sparsity - ); - else - var_sparsity.clear(i_var); - break; - // ------------------------------------------------- - - case DivvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - forward_sparse_jacobian_binary_op( - i_var, arg, var_sparsity - ); - break; - // ------------------------------------------------- - - case DivpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - forward_sparse_jacobian_unary_op( - i_var, arg[1], var_sparsity - ); - break; - // ------------------------------------------------- - - case DivvpOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case EndOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 0); - more_operators = false; - break; - // ------------------------------------------------- - - case ErfOp: - // arg[1] is always the parameter 0 - // arg[0] is always the parameter 2 / sqrt(pi) - CPPAD_ASSERT_NARG_NRES(op, 3, 5); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case ExpOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case Expm1Op: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; -# endif - // ------------------------------------------------- - - case InvOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 1); - // sparsity pattern is already defined - break; - // ------------------------------------------------- - - case LdpOp: - forward_sparse_load_op( - dependency, - op, - i_var, - arg, - num_vecad_ind, - vecad_ind.data(), - var_sparsity, - vecad_sparsity - ); - break; - // ------------------------------------------------- - - case LdvOp: - forward_sparse_load_op( - dependency, - op, - i_var, - arg, - num_vecad_ind, - vecad_ind.data(), - var_sparsity, - vecad_sparsity - ); - break; - // ------------------------------------------------- - - case EqpvOp: - case EqvvOp: - case LtpvOp: - case LtvpOp: - case LtvvOp: - case LepvOp: - case LevpOp: - case LevvOp: - case NepvOp: - case NevvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 0); - break; - // ------------------------------------------------- - - case LogOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case Log1pOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; -# endif - // ------------------------------------------------- - - case MulpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - forward_sparse_jacobian_unary_op( - i_var, arg[1], var_sparsity - ); - break; - // ------------------------------------------------- - - case MulvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - forward_sparse_jacobian_binary_op( - i_var, arg, var_sparsity - ); - break; - // ------------------------------------------------- - - case ParOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - var_sparsity.clear(i_var); - break; - // ------------------------------------------------- - - case PowvpOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 3); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case PowpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 3); - forward_sparse_jacobian_unary_op( - i_var, arg[1], var_sparsity - ); - break; - // ------------------------------------------------- - - case PowvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 3); - forward_sparse_jacobian_binary_op( - i_var, arg, var_sparsity - ); - break; - // ------------------------------------------------- - - case PriOp: - CPPAD_ASSERT_NARG_NRES(op, 5, 0); - break; - // ------------------------------------------------- - - case SignOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - // derivative is identically zero but dependency is not - if( dependency ) forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - else - var_sparsity.clear(i_var); - break; - // ------------------------------------------------- - - case SinOp: - // cos(x), sin(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case SinhOp: - // cosh(x), sinh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case SqrtOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case StppOp: - CPPAD_ASSERT_NARG_NRES(op, 3, 0); - // if both arguments are parameters does not affect sparsity - // or dependency - break; - // ------------------------------------------------- - - case StpvOp: - forward_sparse_store_op( - dependency, - op, - arg, - num_vecad_ind, - vecad_ind.data(), - var_sparsity, - vecad_sparsity - ); - break; - // ------------------------------------------------- - - case StvpOp: - CPPAD_ASSERT_NARG_NRES(op, 3, 0); - forward_sparse_store_op( - dependency, - op, - arg, - num_vecad_ind, - vecad_ind.data(), - var_sparsity, - vecad_sparsity - ); - break; - // ------------------------------------------------- - - case StvvOp: - forward_sparse_store_op( - dependency, - op, - arg, - num_vecad_ind, - vecad_ind.data(), - var_sparsity, - vecad_sparsity - ); - break; - // ------------------------------------------------- - - case SubvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - forward_sparse_jacobian_binary_op( - i_var, arg, var_sparsity - ); - break; - // ------------------------------------------------- - - case SubpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - forward_sparse_jacobian_unary_op( - i_var, arg[1], var_sparsity - ); - break; - // ------------------------------------------------- - - case SubvpOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case TanOp: - // tan(x)^2, tan(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case TanhOp: - // tanh(x)^2, tanh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case UserOp: - // start or end an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( NumRes( UserOp ) == 0 ); - CPPAD_ASSERT_UNKNOWN( NumArg( UserOp ) == 4 ); - if( user_state == user_start ) - { user_index = arg[0]; - user_id = arg[1]; - user_n = arg[2]; - user_m = arg[3]; - user_atom = atomic_base::class_object(user_index); -# ifndef NDEBUG - if( user_atom == CPPAD_NULL ) - { std::string msg = - atomic_base::class_name(user_index) - + ": atomic_base function has been deleted"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - user_pack = user_atom->sparsity() == - atomic_base::pack_sparsity_enum; - user_bool = user_atom->sparsity() == - atomic_base::bool_sparsity_enum; - user_set = user_atom->sparsity() == - atomic_base::set_sparsity_enum; - CPPAD_ASSERT_UNKNOWN( user_pack || user_bool || user_set ); - if( user_pack ) - { if( pack_r.size() != user_n * user_q ) - pack_r.resize( user_n * user_q ); - if( pack_s.size() != user_m * user_q ) - pack_s.resize( user_m * user_q ); - for(i = 0; i < user_n; i++) - for(j = 0; j < user_q; j++) - pack_r[ i * user_q + j] = false; - } - if( user_bool ) - { if( bool_r.size() != user_n * user_q ) - bool_r.resize( user_n * user_q ); - if( bool_s.size() != user_m * user_q ) - bool_s.resize( user_m * user_q ); - for(i = 0; i < user_n; i++) - for(j = 0; j < user_q; j++) - bool_r[ i * user_q + j] = false; - } - if( user_set) - { if(set_r.size() != user_n ) - set_r.resize(user_n); - if(set_s.size() != user_m ) - set_s.resize(user_m); - for(i = 0; i < user_n; i++) - set_r[i].clear(); - } - user_j = 0; - user_i = 0; - user_state = user_arg; - } - else - { CPPAD_ASSERT_UNKNOWN( user_state == user_end ); - CPPAD_ASSERT_UNKNOWN( user_index == size_t(arg[0]) ); - CPPAD_ASSERT_UNKNOWN( user_id == size_t(arg[1]) ); - CPPAD_ASSERT_UNKNOWN( user_n == size_t(arg[2]) ); - CPPAD_ASSERT_UNKNOWN( user_m == size_t(arg[3]) ); -# ifndef NDEBUG - if( ! user_ok ) - { std::string msg = - atomic_base::class_name(user_index) - + ": atomic_base.for_sparse_jac: returned false\n"; - if( user_pack ) - msg += "sparsity = pack_sparsity_enum"; - if( user_bool ) - msg += "sparsity = bool_sparsity_enum"; - if( user_set ) - msg += "sparsity = set_sparsity_enum"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - user_state = user_start; - } - break; - - case UsrapOp: - // parameter argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( user_j < user_n ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - // set row user_j to empty sparsity pattern - ++user_j; - if( user_j == user_n ) - { // call users function for this operation - user_atom->set_id(user_id); - if( user_pack ) - CPPAD_ATOMIC_CALL( user_q, pack_r, pack_s); - if( user_bool ) - CPPAD_ATOMIC_CALL( user_q, bool_r, bool_s); - if( user_set ) - CPPAD_ATOMIC_CALL( user_q, set_r, set_s); - user_state = user_ret; - } - break; - - case UsravOp: - // variable argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( user_j < user_n ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) <= i_var ); - // set row user_j to sparsity pattern for variable arg[0] - var_sparsity.begin(arg[0]); - i = var_sparsity.next_element(); - while( i < user_q ) - { if( user_pack ) - pack_r[user_j * user_q + i] = true; - if( user_bool ) - bool_r[user_j * user_q + i] = true; - if( user_set ) - set_r[user_j].insert(i); - i = var_sparsity.next_element(); - } - ++user_j; - if( user_j == user_n ) - { // call users function for this operation - user_atom->set_id(user_id); - if( user_pack ) - CPPAD_ATOMIC_CALL( user_q, pack_r, pack_s); - if( user_bool ) - CPPAD_ATOMIC_CALL( user_q, bool_r, bool_s); - if( user_set ) - CPPAD_ATOMIC_CALL( user_q, set_r, set_s); - user_state = user_ret; - } - break; - - case UsrrpOp: - // parameter result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( user_i < user_m ); - user_i++; - if( user_i == user_m ) - user_state = user_end; - break; - - case UsrrvOp: - // variable result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( user_i < user_m ); - // It might be faster if we add set union to var_sparsity - // where one of the sets is not in var_sparsity - if( user_pack ) - { for(j = 0; j < user_q; j++) - if( pack_s[ user_i * user_q + j ] ) - var_sparsity.add_element(i_var, j); - } - if( user_bool ) - { for(j = 0; j < user_q; j++) - if( bool_s[ user_i * user_q + j ] ) - var_sparsity.add_element(i_var, j); - } - if( user_set ) - { set_itr = set_s[user_i].begin(); - set_end = set_s[user_i].end(); - while( set_itr != set_end ) - var_sparsity.add_element(i_var, *set_itr++); - } - user_i++; - if( user_i == user_m ) - user_state = user_end; - break; - // ------------------------------------------------- - - case ZmulpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - forward_sparse_jacobian_unary_op( - i_var, arg[1], var_sparsity - ); - break; - // ------------------------------------------------- - - case ZmulvpOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - forward_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case ZmulvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - forward_sparse_jacobian_binary_op( - i_var, arg, var_sparsity - ); - break; - // ------------------------------------------------- - - default: - CPPAD_ASSERT_UNKNOWN(0); - } -# if CPPAD_FOR_JAC_SWEEP_TRACE - const addr_t* arg_tmp = arg; - if( op == CSumOp ) - arg_tmp = arg - arg[-1] - 4; - if( op == CSkipOp ) - arg_tmp = arg - arg[-1] - 7; - // - // value for this variable - for(j = 0; j < limit; j++) - z_value[j] = false; - var_sparsity.begin(i_var); - j = var_sparsity.next_element(); - while( j < limit ) - { z_value[j] = true; - j = var_sparsity.next_element(); - } - printOp( - std::cout, - play, - i_op, - i_var, - op, - arg_tmp - ); - if( NumRes(op) > 0 ) printOpResult( - std::cout, - 1, - &z_value, - 0, - (CppAD::vectorBool *) CPPAD_NULL - ); - std::cout << std::endl; - } - std::cout << std::endl; -# else - } -# endif - CPPAD_ASSERT_UNKNOWN( i_var + 1 == play->num_var_rec() ); - - return; -} - -} // END_CPPAD_NAMESPACE - -// preprocessor symbols that are local to this file -# undef CPPAD_FOR_JAC_SWEEP_TRACE -# undef CPPAD_ATOMIC_CALL - -# endif diff --git a/ct_core/include/ct/external/cppad/local/for_one.hpp b/ct_core/include/ct/external/cppad/local/for_one.hpp deleted file mode 100644 index 7752e6218..000000000 --- a/ct_core/include/ct/external/cppad/local/for_one.hpp +++ /dev/null @@ -1,165 +0,0 @@ -// $Id: for_one.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_FOR_ONE_HPP -# define CPPAD_FOR_ONE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin ForOne$$ -$spell - dy - typename - Taylor - const -$$ - - - - -$section First Order Partial Derivative: Driver Routine$$ -$mindex easy$$ - -$head Syntax$$ -$icode%dy% = %f%.ForOne(%x%, %j%)%$$ - - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -The syntax above sets $icode dy$$ to the -partial of $latex F$$ with respect to $latex x_j$$; i.e., -$latex \[ -dy -= \D{F}{ x_j } (x) -= \left[ - \D{ F_0 }{ x_j } (x) , \cdots , \D{ F_{m-1} }{ x_j } (x) -\right] -\] $$ - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/ForOne Uses Forward/ForOne/ForOne Uses Forward/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -(see $cref/Vector/ForOne/Vector/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the partial derivative. - -$head j$$ -The argument $icode j$$ has prototype -$codei% - size_t %j% -%$$ -an is less than $icode n$$, -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies the component of $icode F$$ -for which we are computing the partial derivative. - -$head dy$$ -The result $icode dy$$ has prototype -$codei% - %Vector% %dy% -%$$ -(see $cref/Vector/ForOne/Vector/$$ below) -and its size is $latex m$$, the dimension of the -$cref/range/seq_property/Range/$$ space for $icode f$$. -The value of $icode dy$$ is the partial of $latex F$$ with respect to -$latex x_j$$ evaluated at $icode x$$; i.e., -for $latex i = 0 , \ldots , m - 1$$ -$latex \[. - dy[i] = \D{ F_i }{ x_j } ( x ) -\] $$ - - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Base$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head ForOne Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to $code ForOne$$, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0,%x%)%$$ -and the other coefficients are unspecified. - -$head Example$$ -$children% - example/for_one.cpp -%$$ -The routine -$cref/ForOne/for_one.cpp/$$ is both an example and test. -It returns $code true$$, if it succeeds and $code false$$ otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -template -Vector ADFun::ForOne(const Vector &x, size_t j) -{ size_t j1; - - size_t n = Domain(); - size_t m = Range(); - - // check Vector is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( - x.size() == n, - "ForOne: Length of x not equal domain dimension for f" - ); - CPPAD_ASSERT_KNOWN( - j < n, - "ForOne: the index j is not less than domain dimension for f" - ); - - // point at which we are evaluating the second partials - Forward(0, x); - - // direction in which are are taking the derivative - Vector dx(n); - for(j1 = 0; j1 < n; j1++) - dx[j1] = Base(0); - dx[j] = Base(1); - - // dimension the return value - Vector dy(m); - - // compute the return value - dy = Forward(1, dx); - - return dy; -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/for_sparse_jac.hpp b/ct_core/include/ct/external/cppad/local/for_sparse_jac.hpp deleted file mode 100644 index de0e75623..000000000 --- a/ct_core/include/ct/external/cppad/local/for_sparse_jac.hpp +++ /dev/null @@ -1,901 +0,0 @@ -// $Id: for_sparse_jac.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_FOR_SPARSE_JAC_HPP -# define CPPAD_FOR_SPARSE_JAC_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin ForSparseJac$$ -$spell - std - var - Jacobian - Jac - const - Bool - proportional - VecAD - CondExpRel - optimizer - cpp -$$ - -$section Jacobian Sparsity Pattern: Forward Mode$$ - -$head Syntax$$ -$icode%s% = %f%.ForSparseJac(%q%, %r%) -%$$ -$icode%s% = %f%.ForSparseJac(%q%, %r%, %transpose%, %dependency%)%$$ - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -For a fixed $latex n \times q$$ matrix $latex R$$, -the Jacobian of $latex F[ x + R * u ]$$ -with respect to $latex u$$ at $latex u = 0$$ is -$latex \[ - S(x) = F^{(1)} ( x ) * R -\] $$ -Given a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for $latex R$$, -$code ForSparseJac$$ returns a sparsity pattern for the $latex S(x)$$. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$. -After a call to $code ForSparseJac$$, the sparsity pattern -for each of the variables in the operation sequence -is held in $icode f$$ (for possible later use by $cref RevSparseHes$$). -These sparsity patterns are stored with elements of type $code bool$$ -or elements of type $code std::set$$ -(see $cref/VectorSet/ForSparseJac/VectorSet/$$ below). - -$subhead size_forward_bool$$ -After $code ForSparseJac$$, if $icode k$$ is a $code size_t$$ object, -$codei% - %k% = %f%.size_forward_bool() -%$$ -sets $icode k$$ to the amount of memory (in unsigned character units) -used to store the sparsity pattern with elements of type $code bool$$ -in the function object $icode f$$. -If the sparsity patterns for the previous $code ForSparseJac$$ used -elements of type $code bool$$, -the return value for $code size_forward_bool$$ will be non-zero. -Otherwise, its return value will be zero. -This sparsity pattern is stored for use by $cref RevSparseHes$$ and -when it is not longer needed, it can be deleted -(and the corresponding memory freed) using -$codei% - %f%.size_forward_bool(0) -%$$ -After this call, $icode%f%.size_forward_bool()%$$ will return zero. - -$subhead size_forward_set$$ -After $code ForSparseJac$$, if $icode k$$ is a $code size_t$$ object, -$codei% - %k% = %f%.size_forward_set() -%$$ -sets $icode s$$ to the total number of elements in all the sets corresponding -to the sparsity pattern stored in the function object $icode f$$. -If the sparsity patterns for this operation use elements of type $code bool$$, -the return value for $code size_forward_set$$ will be zero. -Otherwise, its return value will be non-zero -(unless the entire sparsity pattern is false). -This sparsity pattern is stored for use by $cref RevSparseHes$$ and -when it is not longer needed, it can be deleted -(and the corresponding memory freed) using -$codei% - %f%.size_forward_set(0) -%$$ -After this call, $icode%f%.size_forward_set()%$$ will return zero. - -$head x$$ -the sparsity pattern is valid for all values of the independent -variables in $latex x \in B^n$$ -(even if it has $cref CondExp$$ or $cref VecAD$$ operations). - -$head q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of columns in -$latex R \in B^{n \times q}$$ and the Jacobian -$latex S(x) \in B^{m \times q}$$. - -$head transpose$$ -The argument $icode transpose$$ has prototype -$codei% - bool %transpose% -%$$ -The default value $code false$$ is used when $icode transpose$$ is not present. - -$head dependency$$ -The argument $icode dependency$$ has prototype -$codei% - bool %dependency% -%$$ -If $icode dependency$$ is true, -the $cref/dependency pattern/dependency.cpp/Dependency Pattern/$$ -(instead of sparsity pattern) is computed. - -$head r$$ -The argument $icode r$$ has prototype -$codei% - const %VectorSet%& %r% -%$$ -see $cref/VectorSet/ForSparseJac/VectorSet/$$ below. - -$subhead transpose false$$ -If $icode r$$ has elements of type $code bool$$, -its size is $latex n * q$$. -If it has elements of type $code std::set$$, -its size is $latex n$$ and all the set elements must be between -zero and $icode%q%-1%$$ inclusive. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex R \in B^{n \times q}$$. - -$subhead transpose true$$ -If $icode r$$ has elements of type $code bool$$, -its size is $latex q * n$$. -If it has elements of type $code std::set$$, -its size is $latex q$$ and all the set elements must be between -zero and $icode%n%-1%$$ inclusive. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex R^\R{T} \in B^{q \times n}$$. - -$head s$$ -The return value $icode s$$ has prototype -$codei% - %VectorSet% %s% -%$$ -see $cref/VectorSet/ForSparseJac/VectorSet/$$ below. - -$subhead transpose false$$ -If $icode s$$ has elements of type $code bool$$, -its size is $latex m * q$$. -If it has elements of type $code std::set$$, -its size is $latex m$$ and all its set elements are between -zero and $icode%q%-1%$$ inclusive. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex S(x) \in B^{m \times q}$$. - -$subhead transpose true$$ -If $icode s$$ has elements of type $code bool$$, -its size is $latex q * m$$. -If it has elements of type $code std::set$$, -its size is $latex q$$ and all its set elements are between -zero and $icode%m%-1%$$ inclusive. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex S(x)^\R{T} \in B^{q \times m}$$. - -$head VectorSet$$ -The type $icode VectorSet$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code bool$$ or $code std::set$$; -see $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for a discussion -of the difference. - -$head Entire Sparsity Pattern$$ -Suppose that $latex q = n$$ and -$latex R$$ is the $latex n \times n$$ identity matrix. -In this case, -the corresponding value for $icode s$$ is a -sparsity pattern for the Jacobian $latex S(x) = F^{(1)} ( x )$$. - -$head Example$$ -$children% - example/for_sparse_jac.cpp -%$$ -The file -$cref for_sparse_jac.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. -The file -$cref/sparsity_sub.cpp/sparsity_sub.cpp/ForSparseJac/$$ -contains an example and test of using $code ForSparseJac$$ -to compute the sparsity pattern for a subset of the Jacobian. - -$end ------------------------------------------------------------------------------ -*/ - -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file for_sparse_jac.hpp -Forward mode Jacobian sparsity patterns. -*/ - -// --------------------------------------------------------------------------- -/*! -Calculate Jacobian vector of bools sparsity patterns using forward mode. - -The C++ source code corresponding to this operation is -\verbatim - s = f.ForSparseJac(q, r) -\endverbatim - -\tparam Base -is the base type for this recording. - -\tparam VectorSet -is a simple vector class with elements of type \c bool. - -\param transpose -are the sparsity patterns transposed. - -\param dependency -Are the derivatives with respect to left and right of the expression below -considered to be non-zero: -\code - CondExpRel(left, right, if_true, if_false) -\endcode -This is used by the optimizer to obtain the correct dependency relations. - -\param q -is the number of columns in the matrix \f$ R \f$. - -\param r -is a sparsity pattern for the matrix \f$ R \f$. - -\param s -The input value of \a s must be a vector with size \c m*q -where \c m is the number of dependent variables -corresponding to the operation sequence stored in \a play. -The input value of the components of \c s does not matter. -On output, \a s is the sparsity pattern for the matrix -\f[ - S(x) = F^{(1)} (x) * R -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \a x is any argument value. - -\param total_num_var -is the total number of variable in this recording. - -\param dep_taddr -maps dependendent variable index -to the corresponding variable in the tape. - -\param ind_taddr -maps independent variable index -to the corresponding variable in the tape. - -\param play -is the recording that defines the function we are computing the sparsity -pattern for. - -\param for_jac_sparsity -the input value of \a for_jac_sparsity does not matter. -On output, \a for_jac_sparsity.n_set() == \a total_num_var -and \a for_jac_sparsity.end() == \a q. -It contains the forward sparsity pattern for all of the variables on the -tape (given the sparsity pattern for the independent variables is \f$ R \f$). -*/ -template -void ForSparseJacBool( - bool transpose , - bool dependency , - size_t q , - const VectorSet& r , - VectorSet& s , - size_t total_num_var , - CppAD::vector& dep_taddr , - CppAD::vector& ind_taddr , - CppAD::player& play , - sparse_pack& for_jac_sparsity ) -{ - // temporary indices - size_t i, j; - - // range and domain dimensions for F - size_t m = dep_taddr.size(); - size_t n = ind_taddr.size(); - - CPPAD_ASSERT_KNOWN( - q > 0, - "ForSparseJac: q is not greater than zero" - ); - CPPAD_ASSERT_KNOWN( - size_t(r.size()) == n * q, - "ForSparseJac: size of r is not equal to\n" - "q times domain dimension for ADFun object." - ); - - // allocate memory for the requested sparsity calculation result - for_jac_sparsity.resize(total_num_var, q); - - // set values corresponding to independent variables - for(i = 0; i < n; i++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr[i] < total_num_var ); - // ind_taddr[i] is operator taddr for i-th independent variable - CPPAD_ASSERT_UNKNOWN( play.GetOp( ind_taddr[i] ) == InvOp ); - - // set bits that are true - if( transpose ) - { for(j = 0; j < q; j++) if( r[ j * n + i ] ) - for_jac_sparsity.add_element( ind_taddr[i], j); - } - else - { for(j = 0; j < q; j++) if( r[ i * q + j ] ) - for_jac_sparsity.add_element( ind_taddr[i], j); - } - } - - // evaluate the sparsity patterns - ForJacSweep( - dependency, - n, - total_num_var, - &play, - for_jac_sparsity - ); - - // return values corresponding to dependent variables - CPPAD_ASSERT_UNKNOWN( size_t(s.size()) == m * q ); - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr[i] < total_num_var ); - - // extract the result from for_jac_sparsity - if( transpose ) - { for(j = 0; j < q; j++) - s[ j * m + i ] = false; - } - else - { for(j = 0; j < q; j++) - s[ i * q + j ] = false; - } - CPPAD_ASSERT_UNKNOWN( for_jac_sparsity.end() == q ); - for_jac_sparsity.begin( dep_taddr[i] ); - j = for_jac_sparsity.next_element(); - while( j < q ) - { if( transpose ) - s[j * m + i] = true; - else s[i * q + j] = true; - j = for_jac_sparsity.next_element(); - } - } -} - -/*! -Calculate Jacobian vector of sets sparsity patterns using forward mode. - -The C++ source code corresponding to this operation is -\verbatim - s = f.ForSparseJac(q, r) -\endverbatim - -\tparam Base -see \c SparseJacBool. - -\tparam VectorSet -is a simple vector class with elements of type \c std::set. - -\param transpose -see \c SparseJacBool. - -\param dependency -see \c SparseJacBool. - -\param q -see \c SparseJacBool. - -\param r -see \c SparseJacBool. - -\param s -see \c SparseJacBool. - -\param total_num_var -see \c SparseJacBool. - -\param dep_taddr -see \c SparseJacBool. - -\param ind_taddr -see \c SparseJacBool. - -\param play -see \c SparseJacBool. - -\param for_jac_sparsity -see \c SparseJacBool. -*/ - -template -void ForSparseJacSet( - bool transpose , - bool dependency , - size_t q , - const VectorSet& r , - VectorSet& s , - size_t total_num_var , - CppAD::vector& dep_taddr , - CppAD::vector& ind_taddr , - CppAD::player& play , - CPPAD_INTERNAL_SPARSE_SET& for_jac_sparsity ) -{ - // temporary indices - size_t i, j; - std::set::const_iterator itr; - - // range and domain dimensions for F - size_t m = dep_taddr.size(); - size_t n = ind_taddr.size(); - - CPPAD_ASSERT_KNOWN( - q > 0, - "RevSparseJac: q is not greater than zero" - ); - CPPAD_ASSERT_KNOWN( - size_t(r.size()) == n || transpose, - "RevSparseJac: size of r is not equal to n and transpose is false." - ); - CPPAD_ASSERT_KNOWN( - size_t(r.size()) == q || ! transpose, - "RevSparseJac: size of r is not equal to q and transpose is true." - ); - - // allocate memory for the requested sparsity calculation - for_jac_sparsity.resize(total_num_var, q); - - // set values corresponding to independent variables - if( transpose ) - { for(i = 0; i < q; i++) - { // add the elements that are present - itr = r[i].begin(); - while( itr != r[i].end() ) - { j = *itr++; - CPPAD_ASSERT_KNOWN( - j < n, - "ForSparseJac: transpose is true and element of the set\n" - "r[j] has value greater than or equal n." - ); - CPPAD_ASSERT_UNKNOWN( ind_taddr[j] < total_num_var ); - // operator for j-th independent variable - CPPAD_ASSERT_UNKNOWN( play.GetOp( ind_taddr[j] ) == InvOp ); - for_jac_sparsity.add_element( ind_taddr[j], i); - } - } - } - else - { for(i = 0; i < n; i++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr[i] < total_num_var ); - // ind_taddr[i] is operator taddr for i-th independent variable - CPPAD_ASSERT_UNKNOWN( play.GetOp( ind_taddr[i] ) == InvOp ); - - // add the elements that are present - itr = r[i].begin(); - while( itr != r[i].end() ) - { j = *itr++; - CPPAD_ASSERT_KNOWN( - j < q, - "ForSparseJac: an element of the set r[i] " - "has value greater than or equal q." - ); - for_jac_sparsity.add_element( ind_taddr[i], j); - } - } - } - // evaluate the sparsity patterns - ForJacSweep( - dependency, - n, - total_num_var, - &play, - for_jac_sparsity - ); - - // return values corresponding to dependent variables - CPPAD_ASSERT_UNKNOWN( size_t(s.size()) == m || transpose ); - CPPAD_ASSERT_UNKNOWN( size_t(s.size()) == q || ! transpose ); - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr[i] < total_num_var ); - - // extract results from for_jac_sparsity - // and add corresponding elements to sets in s - CPPAD_ASSERT_UNKNOWN( for_jac_sparsity.end() == q ); - for_jac_sparsity.begin( dep_taddr[i] ); - j = for_jac_sparsity.next_element(); - while( j < q ) - { if( transpose ) - s[j].insert(i); - else s[i].insert(j); - j = for_jac_sparsity.next_element(); - } - } -} -// --------------------------------------------------------------------------- -/*! -Private helper function for ForSparseJac(q, r). - -All of the description in the public member function ForSparseJac(q, r) -applies. - -\param set_type -is a \c bool value. This argument is used to dispatch to the proper source -code depending on the value of \c VectorSet::value_type. - -\param transpose -See \c ForSparseJac(q, r, transpose, dependency). - -\param dependency -See \c ForSparseJac(q, r, transpose, dependency). - -\param q -See \c ForSparseJac(q, r, transpose, dependency). - -\param r -See \c ForSparseJac(q, r, transpose, dependency). - -\param s -is the return value for the corresponding call to \c ForSparseJac(q, r). -*/ - -template -template -void ADFun::ForSparseJacCase( - bool set_type , - bool transpose , - bool dependency , - size_t q , - const VectorSet& r , - VectorSet& s ) -{ size_t m = Range(); - - // check VectorSet is Simple Vector class with bool elements - CheckSimpleVector(); - - // dimension size of result vector - s.resize( m * q ); - - // store results in s and for_jac_sparse_pack_ - ForSparseJacBool( - transpose , - dependency , - q , - r , - s , - num_var_tape_ , - dep_taddr_ , - ind_taddr_ , - play_ , - for_jac_sparse_pack_ - ); -} - - -/*! -Private helper function for \c ForSparseJac(q, r). - -All of the description in the public member function \c ForSparseJac(q, r) -applies. - -\param set_type -is a \c std::set object. -This argument is used to dispatch to the proper source -code depending on the value of \c VectorSet::value_type. - -\param transpose -See \c ForSparseJac(q, r, transpose, dependency). - -\param dependency -See \c ForSparseJac(q, r, transpose, dependency). - -\param q -See \c ForSparseJac(q, r, transpose, dependency). - -\param r -See \c ForSparseJac(q, r, transpose, dependency). - -\param s -is the return value for the corresponding call to \c ForSparseJac(q, r). -*/ -template -template -void ADFun::ForSparseJacCase( - const std::set& set_type , - bool transpose , - bool dependency , - size_t q , - const VectorSet& r , - VectorSet& s ) -{ size_t m = Range(); - - // check VectorSet is Simple Vector class with sets for elements - CheckSimpleVector, VectorSet>( - one_element_std_set(), two_element_std_set() - ); - - // dimension size of result vector - if( transpose ) - s.resize(q); - else s.resize( m ); - - // store results in r and for_jac_sparse_pack_ - CppAD::ForSparseJacSet( - transpose , - dependency , - q , - r , - s , - num_var_tape_ , - dep_taddr_ , - ind_taddr_ , - play_ , - for_jac_sparse_set_ - ); -} -// --------------------------------------------------------------------------- - -/*! -User API for Jacobian sparsity patterns using forward mode. - -The C++ source code corresponding to this operation is -\verbatim - s = f.ForSparseJac(q, r, transpose, dependency) -\endverbatim - -\tparam Base -is the base type for this recording. - -\tparam VectorSet -is a simple vector with elements of type \c bool -or \c std::set. - -\param q -is the number of columns in the matrix \f$ R \f$. - -\param r -is a sparsity pattern for the matrix \f$ R \f$. - -\param transpose -are sparsity patterns for \f$ R \f$ and \f$ S(x) \f$ transposed. - -\param dependency -Are the derivatives with respect to left and right of the expression below -considered to be non-zero: -\code - CondExpRel(left, right, if_true, if_false) -\endcode -This is used by the optimizer to obtain the correct dependency relations. - -\return -The value of \c transpose is false (true), -the return value is a sparsity pattern for \f$ S(x) \f$ (\f$ S(x)^T \f$) where -\f[ - S(x) = F^{(1)} (x) * R -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \a x is any argument value. -If \c VectorSet::value_type is \c bool, -the return value has size \f$ m * q \f$ (\f$ q * m \f$). -where \c m is the number of dependent variables -corresponding to the operation sequence stored in \c f. -If \c VectorSet::value_type is \c std::set, -the return value has size \f$ m \f$ ( \f$ q \f$ ) -and with all its elements between zero and -\f$ q - 1 \f$ ( \f$ m - 1 \f$). - -\par Side Effects -If \c VectorSet::value_type is \c bool, -the forward sparsity pattern for all of the variables on the -tape is stored in \c for_jac_sparse_pack__. -In this case -\verbatim - for_jac_sparse_pack_.n_set() == num_var_tape_ - for_jac_sparse_pack_.end() == q - for_jac_sparse_set_.n_set() == 0 - for_jac_sparse_set_.end() == 0 -\endverbatim -\n -\n -If \c VectorSet::value_type is \c std::set, -the forward sparsity pattern for all of the variables on the -tape is stored in \c for_jac_sparse_set__. -In this case -\verbatim - for_jac_sparse_set_.n_set() == num_var_tape_ - for_jac_sparse_set_.end() == q - for_jac_sparse_pack_.n_set() == 0 - for_jac_sparse_pack_.end() == 0 -\endverbatim -*/ -template -template -VectorSet ADFun::ForSparseJac( - size_t q , - const VectorSet& r , - bool transpose , - bool dependency ) -{ VectorSet s; - typedef typename VectorSet::value_type Set_type; - - // free all memory currently in sparsity patterns - for_jac_sparse_pack_.resize(0, 0); - for_jac_sparse_set_.resize(0, 0); - - ForSparseJacCase( - Set_type() , - transpose , - dependency , - q , - r , - s - ); - - return s; -} -// =========================================================================== -// ForSparseJacCheckpoint -/*! -Forward mode Jacobian sparsity calculation used by checkpoint functions. - -\tparam Base -is the base type for this recording. - -\param transpose -is true (false) s is equal to \f$ S(x) \f$ (\f$ S(x)^T \f$) -where -\f[ - S(x) = F^{(1)} (x) * R -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \f$ x \f$ is any argument value. - -\param q -is the number of columns in the matrix \f$ R \f$. - -\param r -is a sparsity pattern for the matrix \f$ R \f$. - -\param transpose -are the sparsity patterns for \f$ R \f$ and \f$ S(x) \f$ transposed. - -\param dependency -Are the derivatives with respect to left and right of the expression below -considered to be non-zero: -\code - CondExpRel(left, right, if_true, if_false) -\endcode -This is used by the optimizer to obtain the correct dependency relations. - -\param s -The input size and elements of s do not matter. -On output, s is the sparsity pattern for the matrix \f$ S(x) \f$ -or \f$ S(x)^T \f$ depending on transpose. - -\par Side Effects -If \c VectorSet::value_type is \c bool, -the forward sparsity pattern for all of the variables on the -tape is stored in \c for_jac_sparse_pack__. -In this case -\verbatim - for_jac_sparse_pack_.n_set() == num_var_tape_ - for_jac_sparse_pack_.end() == q - for_jac_sparse_set_.n_set() == 0 - for_jac_sparse_set_.end() == 0 -\endverbatim -\n -\n -If \c VectorSet::value_type is \c std::set, -the forward sparsity pattern for all of the variables on the -tape is stored in \c for_jac_sparse_set__. -In this case -\verbatim - for_jac_sparse_set_.n_set() == num_var_tape_ - for_jac_sparse_set_.end() == q - for_jac_sparse_pack_.n_set() == 0 - for_jac_sparse_pack_.end() == 0 -\endverbatim -*/ -template -void ADFun::ForSparseJacCheckpoint( - size_t q , - CPPAD_INTERNAL_SPARSE_SET& r , - bool transpose , - bool dependency , - CPPAD_INTERNAL_SPARSE_SET& s ) -{ size_t n = Domain(); - size_t m = Range(); - -# ifndef NDEBUG - if( transpose ) - { CPPAD_ASSERT_UNKNOWN( r.n_set() == q ); - CPPAD_ASSERT_UNKNOWN( r.end() == n ); - } - else - { CPPAD_ASSERT_UNKNOWN( r.n_set() == n ); - CPPAD_ASSERT_UNKNOWN( r.end() == q ); - } - for(size_t j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] == (j+1) ); - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == InvOp ); - } -# endif - - // free all memory currently in sparsity patterns - for_jac_sparse_pack_.resize(0, 0); - for_jac_sparse_set_.resize(0, 0); - - // allocate new sparsity pattern - for_jac_sparse_set_.resize(num_var_tape_, q); - - // set sparsity pattern for dependent variables - if( transpose ) - { for(size_t i = 0; i < q; i++) - { r.begin(i); - size_t j = r.next_element(); - while( j < n ) - { for_jac_sparse_set_.add_element( ind_taddr_[j], i ); - j = r.next_element(); - } - } - } - else - { for(size_t j = 0; j < n; j++) - { r.begin(j); - size_t i = r.next_element(); - while( i < q ) - { for_jac_sparse_set_.add_element( ind_taddr_[j], i ); - i = r.next_element(); - } - } - } - - // evaluate the sparsity pattern for all variables - ForJacSweep( - dependency, - n, - num_var_tape_, - &play_, - for_jac_sparse_set_ - ); - - // dimension the return value - if( transpose ) - s.resize(q, m); - else - s.resize(m, q); - - // return values corresponding to dependent variables - for(size_t i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - - // extract the result from for_jac_sparse_set_ - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_set_.end() == q ); - for_jac_sparse_set_.begin( dep_taddr_[i] ); - size_t j = for_jac_sparse_set_.next_element(); - while( j < q ) - { if( transpose ) - s.add_element(j, i); - else - s.add_element(i, j); - j = for_jac_sparse_set_.next_element(); - } - } - -} - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/for_two.hpp b/ct_core/include/ct/external/cppad/local/for_two.hpp deleted file mode 100644 index 36b39c226..000000000 --- a/ct_core/include/ct/external/cppad/local/for_two.hpp +++ /dev/null @@ -1,256 +0,0 @@ -// $Id: for_two.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_FOR_TWO_HPP -# define CPPAD_FOR_TWO_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin ForTwo$$ -$spell - ddy - typename - Taylor - const -$$ - - - - - -$section Forward Mode Second Partial Derivative Driver$$ -$mindex order easy$$ - -$head Syntax$$ -$icode%ddy% = %f%.ForTwo(%x%, %j%, %k%)%$$ - - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -The syntax above sets -$latex \[ - ddy [ i * p + \ell ] - = - \DD{ F_i }{ x_{j[ \ell ]} }{ x_{k[ \ell ]} } (x) -\] $$ -for $latex i = 0 , \ldots , m-1$$ -and $latex \ell = 0 , \ldots , p$$, -where $latex p$$ is the size of the vectors $icode j$$ and $icode k$$. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/ForTwo Uses Forward/ForTwo/ForTwo Uses Forward/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %VectorBase% &%x% -%$$ -(see $cref/VectorBase/ForTwo/VectorBase/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the partial derivatives listed above. - -$head j$$ -The argument $icode j$$ has prototype -$codei% - const %VectorSize_t% &%j% -%$$ -(see $cref/VectorSize_t/ForTwo/VectorSize_t/$$ below) -We use $icode p$$ to denote the size of the vector $icode j$$. -All of the indices in $icode j$$ -must be less than $icode n$$; i.e., -for $latex \ell = 0 , \ldots , p-1$$, $latex j[ \ell ] < n$$. - -$head k$$ -The argument $icode k$$ has prototype -$codei% - const %VectorSize_t% &%k% -%$$ -(see $cref/VectorSize_t/ForTwo/VectorSize_t/$$ below) -and its size must be equal to $icode p$$, -the size of the vector $icode j$$. -All of the indices in $icode k$$ -must be less than $icode n$$; i.e., -for $latex \ell = 0 , \ldots , p-1$$, $latex k[ \ell ] < n$$. - -$head ddy$$ -The result $icode ddy$$ has prototype -$codei% - %VectorBase% %ddy% -%$$ -(see $cref/VectorBase/ForTwo/VectorBase/$$ below) -and its size is $latex m * p$$. -It contains the requested partial derivatives; to be specific, -for $latex i = 0 , \ldots , m - 1 $$ -and $latex \ell = 0 , \ldots , p - 1$$ -$latex \[ - ddy [ i * p + \ell ] - = - \DD{ F_i }{ x_{j[ \ell ]} }{ x_{k[ \ell ]} } (x) -\] $$ - -$head VectorBase$$ -The type $icode VectorBase$$ must be a $cref SimpleVector$$ class with -$cref/elements of type Base/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head VectorSize_t$$ -The type $icode VectorSize_t$$ must be a $cref SimpleVector$$ class with -$cref/elements of type size_t/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head ForTwo Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to $code ForTwo$$, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0, %x%)%$$ -and the other coefficients are unspecified. - -$head Examples$$ -$children% - example/for_two.cpp -%$$ -The routine -$cref/ForTwo/for_two.cpp/$$ is both an example and test. -It returns $code true$$, if it succeeds and $code false$$ otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -template -VectorBase ADFun::ForTwo( - const VectorBase &x, - const VectorSize_t &j, - const VectorSize_t &k) -{ size_t i; - size_t j1; - size_t k1; - size_t l; - - size_t n = Domain(); - size_t m = Range(); - size_t p = j.size(); - - // check VectorBase is Simple Vector class with Base type elements - CheckSimpleVector(); - - // check VectorSize_t is Simple Vector class with size_t elements - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( - x.size() == n, - "ForTwo: Length of x not equal domain dimension for f." - ); - CPPAD_ASSERT_KNOWN( - j.size() == k.size(), - "ForTwo: Lenght of the j and k vectors are not equal." - ); - // point at which we are evaluating the second partials - Forward(0, x); - - - // dimension the return value - VectorBase ddy(m * p); - - // allocate memory to hold all possible diagonal Taylor coefficients - // (for large sparse cases, this is not efficient) - VectorBase D(m * n); - - // boolean flag for which diagonal coefficients are computed - CppAD::vector c(n); - for(j1 = 0; j1 < n; j1++) - c[j1] = false; - - // direction vector in argument space - VectorBase dx(n); - for(j1 = 0; j1 < n; j1++) - dx[j1] = Base(0); - - // result vector in range space - VectorBase dy(m); - - // compute the diagonal coefficients that are needed - for(l = 0; l < p; l++) - { j1 = j[l]; - k1 = k[l]; - CPPAD_ASSERT_KNOWN( - j1 < n, - "ForTwo: an element of j not less than domain dimension for f." - ); - CPPAD_ASSERT_KNOWN( - k1 < n, - "ForTwo: an element of k not less than domain dimension for f." - ); - size_t count = 2; - while(count) - { count--; - if( ! c[j1] ) - { // diagonal term in j1 direction - c[j1] = true; - dx[j1] = Base(1); - Forward(1, dx); - - dx[j1] = Base(0); - dy = Forward(2, dx); - for(i = 0; i < m; i++) - D[i * n + j1 ] = dy[i]; - } - j1 = k1; - } - } - // compute all the requested cross partials - for(l = 0; l < p; l++) - { j1 = j[l]; - k1 = k[l]; - if( j1 == k1 ) - { for(i = 0; i < m; i++) - ddy[i * p + l] = Base(2) * D[i * n + j1]; - } - else - { - // cross term in j1 and k1 directions - dx[j1] = Base(1); - dx[k1] = Base(1); - Forward(1, dx); - - dx[j1] = Base(0); - dx[k1] = Base(0); - dy = Forward(2, dx); - - // place result in return value - for(i = 0; i < m; i++) - ddy[i * p + l] = dy[i] - D[i*n+j1] - D[i*n+k1]; - - } - } - return ddy; -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/forward.hpp b/ct_core/include/ct/external/cppad/local/forward.hpp deleted file mode 100644 index 9fbf8bda7..000000000 --- a/ct_core/include/ct/external/cppad/local/forward.hpp +++ /dev/null @@ -1,425 +0,0 @@ -// $Id: forward.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_FORWARD_HPP -# define CPPAD_FORWARD_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// documened after Forward but included here so easy to see -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file forward.hpp -User interface to forward mode computations. -*/ - -/*! -Multiple orders, one direction, forward mode Taylor coefficieints. - -\tparam Base -The type used during the forward mode computations; i.e., the corresponding -recording of operations used the type AD. - -\tparam VectorBase -is a Simple Vector class with eleements of type Base. - -\param q -is the hightest order for this forward mode computation; i.e., -after this calculation there will be q+1 -Taylor coefficients per variable. - -\param xq -contains Taylor coefficients for the independent variables. -The size of xq must either be n or (q+1)*n, -We define p = q + 1 - xq.size()/n. -For j = 0 , ... , n-1, -k = p, ... , q, are -xq[ (q+1-p)*j + k - p ] -is the k-th order coefficient for the j-th independent variable. - -\param s -Is the stream where output corresponding to PriOp operations will written. - -\return -contains Taylor coefficients for the dependent variables. -The size of the return value y is m*(q+1-p). -For i = 0, ... , m-1, -k = p, ..., q, -y[(q+1-p)*i + (k-p)] -is the k-th order coefficient for the i-th dependent variable. - -\par taylor_ -The Taylor coefficients up to order p-1 are inputs -and the coefficents from order p through q are outputs. -Let N = num_var_tape_, and -C = cap_order_taylor_. -Note that for -i = 1 , ..., N-1, -k = 0 , ..., q, -taylor_[ C*i + k ] -is the k-th order cofficent, -for the i-th varaible on the tape. -(The first independent variable has index one on the tape -and there is no variable with index zero.) -*/ - -template -template -VectorBase ADFun::Forward( - size_t q , - const VectorBase& xq , - std::ostream& s ) -{ // temporary indices - size_t i, j, k; - - // number of independent variables - size_t n = ind_taddr_.size(); - - // number of dependent variables - size_t m = dep_taddr_.size(); - - // check Vector is Simple Vector class with Base type elements - CheckSimpleVector(); - - - CPPAD_ASSERT_KNOWN( - size_t(xq.size()) == n || size_t(xq.size()) == n*(q+1), - "Forward(q, xq): xq.size() is not equal n or n*(q+1)" - ); - - // lowest order we are computing - size_t p = q + 1 - size_t(xq.size()) / n; - CPPAD_ASSERT_UNKNOWN( p == 0 || p == q ); - CPPAD_ASSERT_KNOWN( - q <= num_order_taylor_ || p == 0, - "Forward(q, xq): Number of Taylor coefficient orders stored in this" - " ADFun\nis less than q and xq.size() != n*(q+1)." - ); - CPPAD_ASSERT_KNOWN( - p <= 1 || num_direction_taylor_ == 1, - "Forward(q, xq): computing order q >= 2" - " and number of directions is not one." - "\nMust use Forward(q, r, xq) for this case" - ); - // does taylor_ need more orders or fewer directions - if( (cap_order_taylor_ <= q) | (num_direction_taylor_ != 1) ) - { if( p == 0 ) - { // no need to copy old values during capacity_order - num_order_taylor_ = 0; - } - else num_order_taylor_ = q; - size_t c = std::max(q + 1, cap_order_taylor_); - size_t r = 1; - capacity_order(c, r); - } - CPPAD_ASSERT_UNKNOWN( cap_order_taylor_ > q ); - CPPAD_ASSERT_UNKNOWN( num_direction_taylor_ == 1 ); - - // short hand notation for order capacity - size_t C = cap_order_taylor_; - - // set Taylor coefficients for independent variables - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] < num_var_tape_ ); - - // ind_taddr_[j] is operator taddr for j-th independent variable - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == InvOp ); - - if( p == q ) - taylor_[ C * ind_taddr_[j] + q] = xq[j]; - else - { for(k = 0; k <= q; k++) - taylor_[ C * ind_taddr_[j] + k] = xq[ (q+1)*j + k]; - } - } - - // evaluate the derivatives - CPPAD_ASSERT_UNKNOWN( cskip_op_.size() == play_.num_op_rec() ); - CPPAD_ASSERT_UNKNOWN( load_op_.size() == play_.num_load_op_rec() ); - if( q == 0 ) - { forward0sweep(s, true, - n, num_var_tape_, &play_, C, - taylor_.data(), cskip_op_.data(), load_op_, - compare_change_count_, - compare_change_number_, - compare_change_op_index_ - ); - } - else - { forward1sweep(s, true, p, q, - n, num_var_tape_, &play_, C, - taylor_.data(), cskip_op_.data(), load_op_, - compare_change_count_, - compare_change_number_, - compare_change_op_index_ - ); - } - - // return Taylor coefficients for dependent variables - VectorBase yq; - if( p == q ) - { yq.resize(m); - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - yq[i] = taylor_[ C * dep_taddr_[i] + q]; - } - } - else - { yq.resize(m * (q+1) ); - for(i = 0; i < m; i++) - { for(k = 0; k <= q; k++) - yq[ (q+1) * i + k] = - taylor_[ C * dep_taddr_[i] + k ]; - } - } -# ifndef NDEBUG - if( check_for_nan_ ) - { bool ok = true; - size_t index = m; - if( p == 0 ) - { for(i = 0; i < m; i++) - { // Visual Studio 2012, CppAD required in front of isnan ? - if( CppAD::isnan( yq[ (q+1) * i + 0 ] ) ) - { ok = false; - if( index == m ) - index = i; - } - } - } - if( ! ok ) - { CPPAD_ASSERT_UNKNOWN( index < m ); - // - CppAD::vector x0(n); - for(j = 0; j < n; j++) - x0[j] = taylor_[ C * ind_taddr_[j] + 0 ]; - std::string file_name; - put_check_for_nan(x0, file_name); - std::stringstream ss; - ss << - "yq = f.Forward(q, xq): a zero order Taylor coefficient is nan.\n" - "Corresponding independent variables vector was written " - "to binary a file.\n" - "vector_size = " << n << "\n" << - "file_name = " << file_name << "\n" << - "index = " << index << "\n"; - // ss.str() returns a string object with a copy of the current - // contents in the stream buffer. - std::string msg_str = ss.str(); - // msg_str.c_str() returns a pointer to the c-string - // representation of the string object's value. - const char* msg_char_star = msg_str.c_str(); - ErrorHandler::Call( - true, - __LINE__, - __FILE__, - "if( CppAD::isnan( yq[ (q+1) * index + 0 ] )", - msg_char_star - ); - } - CPPAD_ASSERT_KNOWN(ok, - "with the value nan." - ); - if( 0 < q ) - { for(i = 0; i < m; i++) - { for(k = p; k <= q; k++) - { // Studio 2012, CppAD required in front of isnan ? - ok &= ! CppAD::isnan( yq[ (q+1-p)*i + k-p ] ); - } - } - } - CPPAD_ASSERT_KNOWN(ok, - "yq = f.Forward(q, xq): has a non-zero order Taylor coefficient\n" - "with the value nan (but zero order coefficients are not nan)." - ); - } -# endif - - // now we have q + 1 taylor_ coefficient orders per variable - num_order_taylor_ = q + 1; - - return yq; -} - -/*! -One order, multiple directions, forward mode Taylor coefficieints. - -\tparam Base -The type used during the forward mode computations; i.e., the corresponding -recording of operations used the type AD. - -\tparam VectorBase -is a Simple Vector class with eleements of type Base. - -\param q -is the order for this forward mode computation, -q > 0. -There must be at least q Taylor coefficients -per variable before this call. -After this call there will be q+1 -Taylor coefficients per variable. - -\param r -is the number of directions for this calculation. -If q != 1, \c r must be the same as in the previous -call to Forward where \c q was equal to one. - -\param xq -contains Taylor coefficients for the independent variables. -The size of xq must either be r*n, -For j = 0 , ... , n-1, -ell = 0, ... , r-1, -xq[ ( r*j + ell ] -is the q-th order coefficient for the j-th independent variable -and the ell-th direction. - -\return -contains Taylor coefficients for the dependent variables. -The size of the return value \c y is r*m. -For i = 0, ... , m-1, -ell = 0, ... , r-1, -y[ r*i + ell ] -is the q-th order coefficient for the i-th dependent variable -and the ell-th direction. - -\par taylor_ -The Taylor coefficients up to order q-1 are inputs -and the coefficents of order \c q are outputs. -Let N = num_var_tape_, and -C = cap_order_taylor_. -Note that for -i = 1 , ..., N-1, -taylor_[ (C-1)*r*i + i + 0 ] -is the zero order cofficent, -for the i-th varaible, and all directions. -For i = 1 , ..., N-1, -k = 1 , ..., q, -ell = 0 , ..., r-1, -taylor_[ (C-1)*r*i + i + (k-1)*r + ell + 1 ] -is the k-th order cofficent, -for the i-th varaible, and ell-th direction. -(The first independent variable has index one on the tape -and there is no variable with index zero.) -*/ - -template -template -VectorBase ADFun::Forward( - size_t q , - size_t r , - const VectorBase& xq ) -{ // temporary indices - size_t i, j, ell; - - // number of independent variables - size_t n = ind_taddr_.size(); - - // number of dependent variables - size_t m = dep_taddr_.size(); - - // check Vector is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( q > 0, "Forward(q, r, xq): q == 0" ); - CPPAD_ASSERT_KNOWN( - size_t(xq.size()) == r * n, - "Forward(q, r, xq): xq.size() is not equal r * n" - ); - CPPAD_ASSERT_KNOWN( - q <= num_order_taylor_ , - "Forward(q, r, xq): Number of Taylor coefficient orders stored in" - " this ADFun is less than q" - ); - CPPAD_ASSERT_KNOWN( - q == 1 || num_direction_taylor_ == r , - "Forward(q, r, xq): q > 1 and number of Taylor directions r" - " is not same as previous Forward(1, r, xq)" - ); - - // does taylor_ need more orders or new number of directions - if( cap_order_taylor_ <= q || num_direction_taylor_ != r ) - { if( num_direction_taylor_ != r ) - num_order_taylor_ = 1; - - size_t c = std::max(q + 1, cap_order_taylor_); - capacity_order(c, r); - } - CPPAD_ASSERT_UNKNOWN( cap_order_taylor_ > q ); - CPPAD_ASSERT_UNKNOWN( num_direction_taylor_ == r ) - - // short hand notation for order capacity - size_t c = cap_order_taylor_; - - // set Taylor coefficients for independent variables - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] < num_var_tape_ ); - - // ind_taddr_[j] is operator taddr for j-th independent variable - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == InvOp ); - - for(ell = 0; ell < r; ell++) - { size_t index = ((c-1)*r + 1)*ind_taddr_[j] + (q-1)*r + ell + 1; - taylor_[ index ] = xq[ r * j + ell ]; - } - } - - // evaluate the derivatives - CPPAD_ASSERT_UNKNOWN( cskip_op_.size() == play_.num_op_rec() ); - CPPAD_ASSERT_UNKNOWN( load_op_.size() == play_.num_load_op_rec() ); - forward2sweep( - q, - r, - n, - num_var_tape_, - &play_, - c, - taylor_.data(), - cskip_op_.data(), - load_op_ - ); - - // return Taylor coefficients for dependent variables - VectorBase yq; - yq.resize(r * m); - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - for(ell = 0; ell < r; ell++) - { size_t index = ((c-1)*r + 1)*dep_taddr_[i] + (q-1)*r + ell + 1; - yq[ r * i + ell ] = taylor_[ index ]; - } - } -# ifndef NDEBUG - if( check_for_nan_ ) - { bool ok = true; - for(i = 0; i < m; i++) - { for(ell = 0; ell < r; ell++) - { // Studio 2012, CppAD required in front of isnan ? - ok &= ! CppAD::isnan( yq[ r * i + ell ] ); - } - } - CPPAD_ASSERT_KNOWN(ok, - "yq = f.Forward(q, r, xq): has a non-zero order Taylor coefficient\n" - "with the value nan (but zero order coefficients are not nan)." - ); - } -# endif - - // now we have q + 1 taylor_ coefficient orders per variable - num_order_taylor_ = q + 1; - - return yq; -} - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/forward0sweep.hpp b/ct_core/include/ct/external/cppad/local/forward0sweep.hpp deleted file mode 100644 index 3a78b4cd5..000000000 --- a/ct_core/include/ct/external/cppad/local/forward0sweep.hpp +++ /dev/null @@ -1,962 +0,0 @@ -// $Id: forward0sweep.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_FORWARD0SWEEP_HPP -# define CPPAD_FORWARD0SWEEP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file forward0sweep.hpp -Compute zero order forward mode Taylor coefficients. -*/ - -/* -\def CPPAD_ATOMIC_CALL -This avoids warnings when NDEBUG is defined and user_ok is not used. -If NDEBUG is defined, this resolves to -\code - user_atom->forward -\endcode -otherwise, it respolves to -\code - user_ok = user_atom->forward -\endcode -This maco is undefined at the end of this file to facillitate is -use with a different definition in other files. -*/ -# ifdef NDEBUG -# define CPPAD_ATOMIC_CALL user_atom->forward -# else -# define CPPAD_ATOMIC_CALL user_ok = user_atom->forward -# endif - -/*! -\def CPPAD_FORWARD0SWEEP_TRACE -This value is either zero or one. -Zero is the normal operational value. -If it is one, a trace of every forward0sweep computation is printed. -(Note that forward0sweep is not used if CPPAD_USE_FORWARD0SWEEP is zero). -*/ -# define CPPAD_FORWARD0SWEEP_TRACE 0 - -/*! -Compute zero order forward mode Taylor coefficients. - - -\tparam Base -The type used during the forward mode computations; i.e., the corresponding -recording of operations used the type AD. - -\param s_out -Is the stream where output corresponding to PriOp operations will -be written. - -\param print -If print is false, -suppress the output that is otherwise generated by the c PriOp instructions. - -\param n -is the number of independent variables on the tape. - -\param numvar -is the total number of variables on the tape. -This is also equal to the number of rows in the matrix taylor; i.e., -play->num_var_rec(). - -\param play -The information stored in play -is a recording of the operations corresponding to the function -\f[ - F : {\bf R}^n \rightarrow {\bf R}^m -\f] -where \f$ n \f$ is the number of independent variables and -\f$ m \f$ is the number of dependent variables. -\n -\n -The object play is effectly constant. -The exception to this is that while palying back the tape -the object play holds information about the current location -with in the tape and this changes during palyback. - -\param J -Is the number of columns in the coefficient matrix taylor. -This must be greater than or equal one. - - - -\param taylor -\n -\b Input: -For i = 1 , ... , n, -taylor [i * J + 0] -variable with index j on the tape -(these are the independent variables). -\n -\n -\b Output: -For i = n + 1, ... , numvar - 1, -taylor [i * J + 0] -is the zero order Taylor coefficient for the variable with -index i on the tape. - -\param cskip_op -Is a vector with size play->num_op_rec(). -The input value of the elements does not matter. -Upon return, if cskip_op[i] is true, the operator index i -does not affect any of the dependent variable -(given the value of the independent variables). - -\param var_by_load_op -Is a vector with size play->num_load_op_rec(). -The input value of the elements does not matter. -Upon return, -it is the variable index corresponding the result for each load operator. -In the case where the index is zero, -the load operator results in a parameter (not a variable). -Note that the is no variable with index zero on the tape. - -\param compare_change_count -Is the count value for changing number and op_index during -zero order foward mode. - -\param compare_change_number -If compare_change_count is zero, this value is set to zero. -Otherwise, the return value is the number of comparision operations -that have a different result from when the information in -play was recorded. - -\param compare_change_op_index -If compare_change_count is zero, this value is set to zero. -Otherwise it is the operator index (see forward_next) for the count-th -comparision operation that has a different result from when the information in -play was recorded. -*/ - -template -void forward0sweep( - std::ostream& s_out, - bool print, - size_t n, - size_t numvar, - player* play, - size_t J, - Base* taylor, - bool* cskip_op, - pod_vector& var_by_load_op, - size_t compare_change_count, - size_t& compare_change_number, - size_t& compare_change_op_index -) -{ CPPAD_ASSERT_UNKNOWN( J >= 1 ); - CPPAD_ASSERT_UNKNOWN( play->num_var_rec() == numvar ); - - // use p, q, r so other forward sweeps can use code defined here - size_t p = 0; - size_t q = 0; - size_t r = 1; - /* - - */ - // op code for current instruction - OpCode op; - - // index for current instruction - size_t i_op; - - // next variables - size_t i_var; - - // operation argument indices - const addr_t* arg = CPPAD_NULL; - - // initialize the comparision operator counter - if( p == 0 ) - { compare_change_number = 0; - compare_change_op_index = 0; - } - - // If this includes a zero calculation, initialize this information - pod_vector isvar_by_ind; - pod_vector index_by_ind; - if( p == 0 ) - { size_t i; - - // this includes order zero calculation, initialize vector indices - size_t num = play->num_vec_ind_rec(); - if( num > 0 ) - { isvar_by_ind.extend(num); - index_by_ind.extend(num); - for(i = 0; i < num; i++) - { index_by_ind[i] = play->GetVecInd(i); - isvar_by_ind[i] = false; - } - } - // includes zero order, so initialize conditional skip flags - num = play->num_op_rec(); - for(i = 0; i < num; i++) - cskip_op[i] = false; - } - - // work space used by UserOp. - vector user_vx; // empty vecotor - vector user_vy; // empty vecotor - vector user_tx; // argument vector Taylor coefficients - vector user_ty; // result vector Taylor coefficients - size_t user_index = 0; // indentifier for this atomic operation - size_t user_id = 0; // user identifier for this call to operator - size_t user_i = 0; // index in result vector - size_t user_j = 0; // index in argument vector - size_t user_m = 0; // size of result vector - size_t user_n = 0; // size of arugment vector - // - atomic_base* user_atom = CPPAD_NULL; // user's atomic op calculator -# ifndef NDEBUG - bool user_ok = false; // atomic op return value -# endif - // - // next expected operator in a UserOp sequence - enum { user_start, user_arg, user_ret, user_end, user_trace } - user_state = user_start; - - // length of the parameter vector (used by CppAD assert macros) - const size_t num_par = play->num_par_rec(); - - // pointer to the beginning of the parameter vector - const Base* parameter = CPPAD_NULL; - if( num_par > 0 ) - parameter = play->GetPar(); - - // length of the text vector (used by CppAD assert macros) - const size_t num_text = play->num_text_rec(); - - // pointer to the beginning of the text vector - const char* text = CPPAD_NULL; - if( num_text > 0 ) - text = play->GetTxt(0); - /* - - */ - -# if CPPAD_FORWARD0SWEEP_TRACE - // variable indices for results vector - // (done differently for order zero). - vector user_iy; -# endif - - // skip the BeginOp at the beginning of the recording - play->forward_start(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( op == BeginOp ); -# if CPPAD_FORWARD0SWEEP_TRACE - std::cout << std::endl; -# endif - bool more_operators = true; - while(more_operators) - { - // this op - play->forward_next(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( (i_op > n) | (op == InvOp) ); - CPPAD_ASSERT_UNKNOWN( (i_op <= n) | (op != InvOp) ); - CPPAD_ASSERT_UNKNOWN( i_op < play->num_op_rec() ); - CPPAD_ASSERT_ARG_BEFORE_RESULT(op, arg, i_var); - - // check if we are skipping this operation - while( cskip_op[i_op] ) - { if( op == CSumOp ) - { // CSumOp has a variable number of arguments - play->forward_csum(op, arg, i_op, i_var); - } - CPPAD_ASSERT_UNKNOWN( op != CSkipOp ); - // if( op == CSkipOp ) - // { // CSkip has a variable number of arguments - // play->forward_cskip(op, arg, i_op, i_var); - // } - play->forward_next(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( i_op < play->num_op_rec() ); - } - - // action to take depends on the case - switch( op ) - { - case AbsOp: - forward_abs_op_0(i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case AddvvOp: - forward_addvv_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case AddpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_addpv_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case AcosOp: - // sqrt(1 - x * x), acos(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_acos_op_0(i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AcoshOp: - // sqrt(x * x - 1), acosh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_acosh_op_0(i_var, arg[0], J, taylor); - break; -# endif - // ------------------------------------------------- - - case AsinOp: - // sqrt(1 - x * x), asin(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_asin_op_0(i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AsinhOp: - // sqrt(1 + x * x), asinh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_asinh_op_0(i_var, arg[0], J, taylor); - break; -# endif - // ------------------------------------------------- - - case AtanOp: - // 1 + x * x, atan(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_atan_op_0(i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AtanhOp: - // 1 - x * x, atanh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_atanh_op_0(i_var, arg[0], J, taylor); - break; -# endif - // ------------------------------------------------- - - case CExpOp: - // Use the general case with d == 0 - // (could create an optimzied verison for this case) - forward_cond_op_0( - i_var, arg, num_par, parameter, J, taylor - ); - break; - // --------------------------------------------------- - - case CosOp: - // sin(x), cos(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_cos_op_0(i_var, arg[0], J, taylor); - break; - // --------------------------------------------------- - - case CoshOp: - // sinh(x), cosh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_cosh_op_0(i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case CSkipOp: - // CSkipOp has a variable number of arguments and - // forward_next thinks it has no arguments. - // we must inform forward_next of this special case. - forward_cskip_op_0( - i_var, arg, num_par, parameter, J, taylor, cskip_op - ); - play->forward_cskip(op, arg, i_op, i_var); - break; - // ------------------------------------------------- - - case CSumOp: - // CSumOp has a variable number of arguments and - // forward_next thinks it has no arguments. - // we must inform forward_next of this special case. - forward_csum_op( - 0, 0, i_var, arg, num_par, parameter, J, taylor - ); - play->forward_csum(op, arg, i_op, i_var); - break; - // ------------------------------------------------- - - case DisOp: - forward_dis_op(p, q, r, i_var, arg, J, taylor); - break; - // ------------------------------------------------- - - case DivvvOp: - forward_divvv_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case DivpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_divpv_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case DivvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - forward_divvp_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case EndOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 0); - more_operators = false; - break; - // ------------------------------------------------- - - case EqpvOp: - if( compare_change_count ) - { forward_eqpv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - { if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - } - break; - // ------------------------------------------------- - - case EqvvOp: - if( compare_change_count ) - { forward_eqvv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - { if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - } - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case ErfOp: - forward_erf_op_0(i_var, arg, parameter, J, taylor); - break; -# endif - // ------------------------------------------------- - - case ExpOp: - forward_exp_op_0(i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case Expm1Op: - forward_expm1_op_0(i_var, arg[0], J, taylor); - break; -# endif - // ------------------------------------------------- - - case InvOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 1); - break; - // --------------------------------------------------- - - case LdpOp: - forward_load_p_op_0( - play, - i_var, - arg, - parameter, - J, - taylor, - isvar_by_ind.data(), - index_by_ind.data(), - var_by_load_op.data() - ); - break; - // ------------------------------------------------- - - case LdvOp: - forward_load_v_op_0( - play, - i_var, - arg, - parameter, - J, - taylor, - isvar_by_ind.data(), - index_by_ind.data(), - var_by_load_op.data() - ); - break; - // ------------------------------------------------- - - case LepvOp: - if( compare_change_count ) - { forward_lepv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - { if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - } - break; - // ------------------------------------------------- - - case LevpOp: - if( compare_change_count ) - { forward_levp_op_0( - compare_change_number, arg, parameter, J, taylor - ); - { if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - } - break; - // ------------------------------------------------- - - case LevvOp: - if( compare_change_count ) - { forward_levv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - { if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - } - break; - // ------------------------------------------------- - - case LogOp: - forward_log_op_0(i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case Log1pOp: - forward_log1p_op_0(i_var, arg[0], J, taylor); - break; -# endif - // ------------------------------------------------- - - case LtpvOp: - if( compare_change_count ) - { forward_ltpv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - { if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - } - break; - // ------------------------------------------------- - - case LtvpOp: - if( compare_change_count ) - { forward_ltvp_op_0( - compare_change_number, arg, parameter, J, taylor - ); - { if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - } - break; - // ------------------------------------------------- - - case LtvvOp: - if( compare_change_count ) - { forward_ltvv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - { if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - } - break; - // ------------------------------------------------- - - case MulpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_mulpv_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case MulvvOp: - forward_mulvv_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case NepvOp: - if( compare_change_count ) - { forward_nepv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - { if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - } - break; - // ------------------------------------------------- - - case NevvOp: - if( compare_change_count ) - { forward_nevv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - { if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - } - break; - // ------------------------------------------------- - - case ParOp: - forward_par_op_0( - i_var, arg, num_par, parameter, J, taylor - ); - break; - // ------------------------------------------------- - - case PowvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - forward_powvp_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case PowpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_powpv_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case PowvvOp: - forward_powvv_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case PriOp: - if( print ) forward_pri_0(s_out, - arg, num_text, text, num_par, parameter, J, taylor - ); - break; - // ------------------------------------------------- - - case SignOp: - // cos(x), sin(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_sign_op_0(i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case SinOp: - // cos(x), sin(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_sin_op_0(i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case SinhOp: - // cosh(x), sinh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_sinh_op_0(i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case SqrtOp: - forward_sqrt_op_0(i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case StppOp: - forward_store_pp_op_0( - i_var, - arg, - num_par, - J, - taylor, - isvar_by_ind.data(), - index_by_ind.data() - ); - break; - // ------------------------------------------------- - - case StpvOp: - forward_store_pv_op_0( - i_var, - arg, - num_par, - J, - taylor, - isvar_by_ind.data(), - index_by_ind.data() - ); - break; - // ------------------------------------------------- - - case StvpOp: - forward_store_vp_op_0( - i_var, - arg, - num_par, - J, - taylor, - isvar_by_ind.data(), - index_by_ind.data() - ); - break; - // ------------------------------------------------- - - case StvvOp: - forward_store_vv_op_0( - i_var, - arg, - num_par, - J, - taylor, - isvar_by_ind.data(), - index_by_ind.data() - ); - break; - // ------------------------------------------------- - - case SubvvOp: - forward_subvv_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case SubpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_subpv_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case SubvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - forward_subvp_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case TanOp: - // tan(x)^2, tan(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_tan_op_0(i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case TanhOp: - // tanh(x)^2, tanh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_tanh_op_0(i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case UserOp: - // start or end an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( NumRes( UserOp ) == 0 ); - CPPAD_ASSERT_UNKNOWN( NumArg( UserOp ) == 4 ); - if( user_state == user_start ) - { user_index = arg[0]; - user_id = arg[1]; - user_n = arg[2]; - user_m = arg[3]; - user_atom = atomic_base::class_object(user_index); -# ifndef NDEBUG - if( user_atom == CPPAD_NULL ) - { std::string msg = - atomic_base::class_name(user_index) - + ": atomic_base function has been deleted"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - if(user_tx.size() != user_n) - user_tx.resize(user_n); - if(user_ty.size() != user_m) - user_ty.resize(user_m); -# if CPPAD_FORWARD0SWEEP_TRACE - if( user_iy.size() != user_m ) - user_iy.resize(user_m); -# endif - user_j = 0; - user_i = 0; - user_state = user_arg; - } - else - { CPPAD_ASSERT_UNKNOWN( user_state == user_end ); - CPPAD_ASSERT_UNKNOWN( user_index == size_t(arg[0]) ); - CPPAD_ASSERT_UNKNOWN( user_id == size_t(arg[1]) ); - CPPAD_ASSERT_UNKNOWN( user_n == size_t(arg[2]) ); - CPPAD_ASSERT_UNKNOWN( user_m == size_t(arg[3]) ); -# ifndef NDEBUG - if( ! user_ok ) - { std::string msg = - atomic_base::class_name(user_index) - + ": atomic_base.forward: returned false"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif -# if CPPAD_FORWARD0SWEEP_TRACE - user_state = user_trace; -# else - user_state = user_start; -# endif - } - break; - - case UsrapOp: - // parameter argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( user_j < user_n ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - user_tx[user_j++] = parameter[ arg[0] ]; - if( user_j == user_n ) - { // call users function for this operation - user_atom->set_id(user_id); - CPPAD_ATOMIC_CALL(p, q, - user_vx, user_vy, user_tx, user_ty - ); - user_state = user_ret; - } - break; - - case UsravOp: - // variable argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( user_j < user_n ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) <= i_var ); - user_tx[user_j++] = taylor[ arg[0] * J + 0 ]; - if( user_j == user_n ) - { // call users function for this operation - user_atom->set_id(user_id); - CPPAD_ATOMIC_CALL(p, q, - user_vx, user_vy, user_tx, user_ty - ); - user_state = user_ret; - } - break; - - case UsrrpOp: - // parameter result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( user_i < user_m ); -# if CPPAD_FORWARD0SWEEP_TRACE - user_iy[user_i] = 0; -# endif - user_i++; - if( user_i == user_m ) - user_state = user_end; - break; - - case UsrrvOp: - // variable result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( user_i < user_m ); -# if CPPAD_FORWARD0SWEEP_TRACE - user_iy[user_i] = i_var; -# endif - taylor[ i_var * J + 0 ] = user_ty[user_i++]; - if( user_i == user_m ) - user_state = user_end; - break; - // ------------------------------------------------- - - case ZmulpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_zmulpv_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case ZmulvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - forward_zmulvp_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case ZmulvvOp: - forward_zmulvv_op_0(i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - default: - CPPAD_ASSERT_UNKNOWN(false); - } -# if CPPAD_FORWARD0SWEEP_TRACE - size_t d = 0; - if( user_state == user_trace ) - { user_state = user_start; - - CPPAD_ASSERT_UNKNOWN( op == UserOp ); - CPPAD_ASSERT_UNKNOWN( NumArg(UsrrvOp) == 0 ); - for(size_t i = 0; i < user_m; i++) if( user_iy[i] > 0 ) - { size_t i_tmp = (i_op + i) - user_m; - printOp( - std::cout, - play, - i_tmp, - user_iy[i], - UsrrvOp, - CPPAD_NULL - ); - Base* Z_tmp = taylor + user_iy[i] * J; - printOpResult( - std::cout, - d + 1, - Z_tmp, - 0, - (Base *) CPPAD_NULL - ); - std::cout << std::endl; - } - } - Base* Z_tmp = taylor + i_var * J; - const addr_t* arg_tmp = arg; - if( op == CSumOp ) - arg_tmp = arg - arg[-1] - 4; - if( op == CSkipOp ) - arg_tmp = arg - arg[-1] - 7; - if( op != UsrrvOp ) - { - printOp( - std::cout, - play, - i_op, - i_var, - op, - arg_tmp - ); - if( NumRes(op) > 0 ) printOpResult( - std::cout, - d + 1, - Z_tmp, - 0, - (Base *) CPPAD_NULL - ); - std::cout << std::endl; - } - } - std::cout << std::endl; -# else - } -# endif - CPPAD_ASSERT_UNKNOWN( user_state == user_start ); - CPPAD_ASSERT_UNKNOWN( i_var + 1 == play->num_var_rec() ); - - return; -} - -} // END_CPPAD_NAMESPACE - -// preprocessor symbols that are local to this file -# undef CPPAD_FORWARD0SWEEP_TRACE -# undef CPPAD_ATOMIC_CALL - -# endif diff --git a/ct_core/include/ct/external/cppad/local/forward1sweep.hpp b/ct_core/include/ct/external/cppad/local/forward1sweep.hpp deleted file mode 100644 index ccd4045e9..000000000 --- a/ct_core/include/ct/external/cppad/local/forward1sweep.hpp +++ /dev/null @@ -1,1073 +0,0 @@ -// $Id: forward1sweep.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_FORWARD1SWEEP_HPP -# define CPPAD_FORWARD1SWEEP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file forward1sweep.hpp -Compute one Taylor coefficient for each order requested. -*/ - -/* -\def CPPAD_ATOMIC_CALL -This avoids warnings when NDEBUG is defined and user_ok is not used. -If NDEBUG is defined, this resolves to -\code - user_atom->forward -\endcode -otherwise, it respolves to -\code - user_ok = user_atom->forward -\endcode -This macro is undefined at the end of this file to facillitate its -use with a different definition in other files. -*/ -# ifdef NDEBUG -# define CPPAD_ATOMIC_CALL user_atom->forward -# else -# define CPPAD_ATOMIC_CALL user_ok = user_atom->forward -# endif - -/*! -\def CPPAD_FORWARD1SWEEP_TRACE -This value is either zero or one. -Zero is the normal operational value. -If it is one, a trace of every forward1sweep computation is printed. -*/ -# define CPPAD_FORWARD1SWEEP_TRACE 0 - -/*! -Compute arbitrary order forward mode Taylor coefficients. - - -\tparam Base -The type used during the forward mode computations; i.e., the corresponding -recording of operations used the type AD. - -\param s_out -Is the stream where output corresponding to PriOp operations will -be written. - -\param print -If print is false, -suppress the output that is otherwise generated by the c PriOp instructions. - -\param n -is the number of independent variables on the tape. - -\param numvar -is the total number of variables on the tape. -This is also equal to the number of rows in the matrix taylor; i.e., -play->num_var_rec(). - -\param play -The information stored in play -is a recording of the operations corresponding to the function -\f[ - F : {\bf R}^n \rightarrow {\bf R}^m -\f] -where \f$ n \f$ is the number of independent variables and -\f$ m \f$ is the number of dependent variables. -\n -\n -The object play is effectly constant. -The exception to this is that while palying back the tape -the object play holds information about the current location -with in the tape and this changes during palyback. - -\param J -Is the number of columns in the coefficient matrix taylor. -This must be greater than or equal one. - - - -\param cskip_op -Is a vector with size play->num_op_rec(). -\n -\n -p = 0 -\n -In this case, -the input value of the elements does not matter. -Upon return, if cskip_op[i] is true, the operator with index i -does not affect any of the dependent variable -(given the value of the independent variables). -\n -\n -p > 0 -\n -In this case cskip_op is not modified and has the same meaning -as its return value above. - -\param var_by_load_op -is a vector with size play->num_load_op_rec(). -\n -\n -p == 0 -\n -In this case, -The input value of the elements does not matter. -Upon return, -it is the variable index corresponding the result for each load operator. -In the case where the index is zero, -the load operator results in a parameter (not a variable). -Note that the is no variable with index zero on the tape. -\n -\n -p > 0 -\n -In this case var_by_load_op is not modified and has the meaning -as its return value above. - -\param p -is the lowest order of the Taylor coefficients -that are computed during this call. - -\param q -is the highest order of the Taylor coefficients -that are computed during this call. - -\param taylor -\n -\b Input: -For i = 1 , ... , numvar-1, -k = 0 , ... , p-1, -taylor[ J*i + k] -is the k-th order Taylor coefficient corresponding to -the i-th variable. -\n -\n -\b Input: -For i = 1 , ... , n, -k = p , ... , q, -taylor[ J*j + k] -is the k-th order Taylor coefficient corresponding to -the i-th variable -(these are the independent varaibles). -\n -\n -\b Output: -For i = n+1 , ... , numvar-1, and -k = 0 , ... , p-1, -taylor[ J*i + k] -is the k-th order Taylor coefficient corresponding to -the i-th variable. - - -\param compare_change_count -Is the count value for changing number and op_index during -zero order foward mode. - -\param compare_change_number -If p is non-zero, this value is not changed, otherwise: -If compare_change_count is zero, this value is set to zero, otherwise: -this value is set to the number of comparision operations -that have a different result from when the information in -play was recorded. - -\param compare_change_op_index -if p is non-zero, this value is not changed, otherwise: -If compare_change_count is zero, this value is set to zero. -Otherwise it is the operator index (see forward_next) for the count-th -comparision operation that has a different result from when the information in -play was recorded. -*/ - -template -void forward1sweep( - std::ostream& s_out, - const bool print, - const size_t p, - const size_t q, - const size_t n, - const size_t numvar, - player* play, - const size_t J, - Base* taylor, - bool* cskip_op, - pod_vector& var_by_load_op, - size_t compare_change_count, - size_t& compare_change_number, - size_t& compare_change_op_index -) -{ - // number of directions - const size_t r = 1; - - CPPAD_ASSERT_UNKNOWN( p <= q ); - CPPAD_ASSERT_UNKNOWN( J >= q + 1 ); - CPPAD_ASSERT_UNKNOWN( play->num_var_rec() == numvar ); - - /* - - */ - // op code for current instruction - OpCode op; - - // index for current instruction - size_t i_op; - - // next variables - size_t i_var; - - // operation argument indices - const addr_t* arg = CPPAD_NULL; - - // initialize the comparision operator counter - if( p == 0 ) - { compare_change_number = 0; - compare_change_op_index = 0; - } - - // If this includes a zero calculation, initialize this information - pod_vector isvar_by_ind; - pod_vector index_by_ind; - if( p == 0 ) - { size_t i; - - // this includes order zero calculation, initialize vector indices - size_t num = play->num_vec_ind_rec(); - if( num > 0 ) - { isvar_by_ind.extend(num); - index_by_ind.extend(num); - for(i = 0; i < num; i++) - { index_by_ind[i] = play->GetVecInd(i); - isvar_by_ind[i] = false; - } - } - // includes zero order, so initialize conditional skip flags - num = play->num_op_rec(); - for(i = 0; i < num; i++) - cskip_op[i] = false; - } - - // work space used by UserOp. - vector user_vx; // empty vecotor - vector user_vy; // empty vecotor - vector user_tx; // argument vector Taylor coefficients - vector user_ty; // result vector Taylor coefficients - size_t user_index = 0; // indentifier for this atomic operation - size_t user_id = 0; // user identifier for this call to operator - size_t user_i = 0; // index in result vector - size_t user_j = 0; // index in argument vector - size_t user_m = 0; // size of result vector - size_t user_n = 0; // size of arugment vector - // - atomic_base* user_atom = CPPAD_NULL; // user's atomic op calculator -# ifndef NDEBUG - bool user_ok = false; // atomic op return value -# endif - // - // next expected operator in a UserOp sequence - enum { user_start, user_arg, user_ret, user_end, user_trace } - user_state = user_start; - - // length of the parameter vector (used by CppAD assert macros) - const size_t num_par = play->num_par_rec(); - - // pointer to the beginning of the parameter vector - const Base* parameter = CPPAD_NULL; - if( num_par > 0 ) - parameter = play->GetPar(); - - // length of the text vector (used by CppAD assert macros) - const size_t num_text = play->num_text_rec(); - - // pointer to the beginning of the text vector - const char* text = CPPAD_NULL; - if( num_text > 0 ) - text = play->GetTxt(0); - /* - - */ - // temporary indices - size_t i, k; - - // number of orders for this user calculation - // (not needed for order zero) - const size_t user_q1 = q+1; - - // variable indices for results vector - // (done differently for order zero). - vector user_iy; - - // skip the BeginOp at the beginning of the recording - play->forward_start(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( op == BeginOp ); -# if CPPAD_FORWARD1SWEEP_TRACE - std::cout << std::endl; -# endif - bool more_operators = true; - while(more_operators) - { - // this op - play->forward_next(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( (i_op > n) | (op == InvOp) ); - CPPAD_ASSERT_UNKNOWN( (i_op <= n) | (op != InvOp) ); - CPPAD_ASSERT_UNKNOWN( i_op < play->num_op_rec() ); - CPPAD_ASSERT_ARG_BEFORE_RESULT(op, arg, i_var); - - // check if we are skipping this operation - while( cskip_op[i_op] ) - { if( op == CSumOp ) - { // CSumOp has a variable number of arguments - play->forward_csum(op, arg, i_op, i_var); - } - CPPAD_ASSERT_UNKNOWN( op != CSkipOp ); - // if( op == CSkipOp ) - // { // CSkip has a variable number of arguments - // play->forward_cskip(op, arg, i_op, i_var); - // } - play->forward_next(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( i_op < play->num_op_rec() ); - } - - // action depends on the operator - switch( op ) - { - case AbsOp: - forward_abs_op(p, q, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case AddvvOp: - forward_addvv_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case AddpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_addpv_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case AcosOp: - // sqrt(1 - x * x), acos(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_acos_op(p, q, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AcoshOp: - // sqrt(x * x - 1), acosh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_acosh_op(p, q, i_var, arg[0], J, taylor); - break; -# endif - // ------------------------------------------------- - - case AsinOp: - // sqrt(1 - x * x), asin(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_asin_op(p, q, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AsinhOp: - // sqrt(1 + x * x), asinh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_asinh_op(p, q, i_var, arg[0], J, taylor); - break; -# endif - // ------------------------------------------------- - - case AtanOp: - // 1 + x * x, atan(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_atan_op(p, q, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AtanhOp: - // 1 - x * x, atanh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_atanh_op(p, q, i_var, arg[0], J, taylor); - break; -# endif - // ------------------------------------------------- - - case CExpOp: - forward_cond_op( - p, q, i_var, arg, num_par, parameter, J, taylor - ); - break; - // --------------------------------------------------- - - case CosOp: - // sin(x), cos(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_cos_op(p, q, i_var, arg[0], J, taylor); - break; - // --------------------------------------------------- - - case CoshOp: - // sinh(x), cosh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_cosh_op(p, q, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case CSkipOp: - // CSkipOp has a variable number of arguments and - // forward_next thinks it has no arguments. - // we must inform forward_next of this special case. - if( p == 0 ) - { forward_cskip_op_0( - i_var, arg, num_par, parameter, J, taylor, cskip_op - ); - } - play->forward_cskip(op, arg, i_op, i_var); - break; - // ------------------------------------------------- - - case CSumOp: - // CSumOp has a variable number of arguments and - // forward_next thinks it has no arguments. - // we must inform forward_next of this special case. - forward_csum_op( - p, q, i_var, arg, num_par, parameter, J, taylor - ); - play->forward_csum(op, arg, i_op, i_var); - break; - // ------------------------------------------------- - - case DisOp: - forward_dis_op(p, q, r, i_var, arg, J, taylor); - break; - // ------------------------------------------------- - - case DivvvOp: - forward_divvv_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case DivpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_divpv_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case DivvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - forward_divvp_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case EndOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 0); - more_operators = false; - break; - // ------------------------------------------------- - - case EqpvOp: - if( ( p == 0 ) & ( compare_change_count > 0 ) ) - { forward_eqpv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - break; - // ------------------------------------------------- - - case EqvvOp: - if( ( p == 0 ) & ( compare_change_count > 0 ) ) - { forward_eqvv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case ErfOp: - CPPAD_ASSERT_UNKNOWN( CPPAD_USE_CPLUSPLUS_2011 ); - // 2DO: implement zero order version of this function - forward_erf_op(p, q, i_var, arg, parameter, J, taylor); - break; -# endif - // ------------------------------------------------- - - case ExpOp: - forward_exp_op(p, q, i_var, arg[0], J, taylor); - break; - // --------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case Expm1Op: - forward_expm1_op(p, q, i_var, arg[0], J, taylor); - break; -# endif - // --------------------------------------------------- - - case InvOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 1); - break; - // ------------------------------------------------- - - case LdpOp: - if( p == 0 ) - { forward_load_p_op_0( - play, - i_var, - arg, - parameter, - J, - taylor, - isvar_by_ind.data(), - index_by_ind.data(), - var_by_load_op.data() - ); - if( p < q ) forward_load_op( - play, - op, - p+1, - q, - r, - J, - i_var, - arg, - var_by_load_op.data(), - taylor - ); - } - else forward_load_op( - play, - op, - p, - q, - r, - J, - i_var, - arg, - var_by_load_op.data(), - taylor - ); - break; - // ------------------------------------------------- - - case LdvOp: - if( p == 0 ) - { forward_load_v_op_0( - play, - i_var, - arg, - parameter, - J, - taylor, - isvar_by_ind.data(), - index_by_ind.data(), - var_by_load_op.data() - ); - if( p < q ) forward_load_op( - play, - op, - p+1, - q, - r, - J, - i_var, - arg, - var_by_load_op.data(), - taylor - ); - } - else forward_load_op( - play, - op, - p, - q, - r, - J, - i_var, - arg, - var_by_load_op.data(), - taylor - ); - break; - // ------------------------------------------------- - - case LepvOp: - if( ( p == 0 ) & ( compare_change_count > 0 ) ) - { forward_lepv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - break; - - case LevpOp: - if( ( p == 0 ) & ( compare_change_count > 0 ) ) - { forward_levp_op_0( - compare_change_number, arg, parameter, J, taylor - ); - if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - break; - // ------------------------------------------------- - - case LevvOp: - if( ( p == 0 ) & ( compare_change_count > 0 ) ) - { forward_levv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - break; - // ------------------------------------------------- - - case LogOp: - forward_log_op(p, q, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case Log1pOp: - forward_log1p_op(p, q, i_var, arg[0], J, taylor); - break; -# endif - // ------------------------------------------------- - - case LtpvOp: - if( ( p == 0 ) & ( compare_change_count > 0 ) ) - { forward_ltpv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - break; - - case LtvpOp: - if( ( p == 0 ) & ( compare_change_count > 0 ) ) - { forward_ltvp_op_0( - compare_change_number, arg, parameter, J, taylor - ); - if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - break; - // ------------------------------------------------- - - case LtvvOp: - if( ( p == 0 ) & ( compare_change_count > 0 ) ) - { forward_ltvv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - break; - // ------------------------------------------------- - - case MulpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_mulpv_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case MulvvOp: - forward_mulvv_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case NepvOp: - if( ( p == 0 ) & ( compare_change_count > 0 ) ) - { forward_nepv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - break; - // ------------------------------------------------- - - case NevvOp: - if( ( p == 0 ) & ( compare_change_count > 0 ) ) - { forward_nevv_op_0( - compare_change_number, arg, parameter, J, taylor - ); - if( compare_change_count == compare_change_number ) - compare_change_op_index = i_op; - } - break; - // ------------------------------------------------- - - case ParOp: - i = p; - if( i == 0 ) - { forward_par_op_0( - i_var, arg, num_par, parameter, J, taylor - ); - i++; - } - while(i <= q) - { taylor[ i_var * J + i] = Base(0); - i++; - } - break; - // ------------------------------------------------- - - case PowvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - forward_powvp_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case PowpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_powpv_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case PowvvOp: - forward_powvv_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case PriOp: - if( (p == 0) & print ) forward_pri_0(s_out, - arg, num_text, text, num_par, parameter, J, taylor - ); - break; - // ------------------------------------------------- - - case SignOp: - // sign(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_sign_op(p, q, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case SinOp: - // cos(x), sin(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_sin_op(p, q, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case SinhOp: - // cosh(x), sinh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_sinh_op(p, q, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case SqrtOp: - forward_sqrt_op(p, q, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case StppOp: - if( p == 0 ) - { forward_store_pp_op_0( - i_var, - arg, - num_par, - J, - taylor, - isvar_by_ind.data(), - index_by_ind.data() - ); - } - break; - // ------------------------------------------------- - - case StpvOp: - if( p == 0 ) - { forward_store_pv_op_0( - i_var, - arg, - num_par, - J, - taylor, - isvar_by_ind.data(), - index_by_ind.data() - ); - } - break; - // ------------------------------------------------- - - case StvpOp: - if( p == 0 ) - { forward_store_vp_op_0( - i_var, - arg, - num_par, - J, - taylor, - isvar_by_ind.data(), - index_by_ind.data() - ); - } - break; - // ------------------------------------------------- - - case StvvOp: - if( p == 0 ) - { forward_store_vv_op_0( - i_var, - arg, - num_par, - J, - taylor, - isvar_by_ind.data(), - index_by_ind.data() - ); - } - break; - // ------------------------------------------------- - - case SubvvOp: - forward_subvv_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case SubpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_subpv_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case SubvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - forward_subvp_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case TanOp: - // tan(x)^2, tan(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_tan_op(p, q, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case TanhOp: - // tanh(x)^2, tanh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_tanh_op(p, q, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case UserOp: - // start or end an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( NumRes( UserOp ) == 0 ); - CPPAD_ASSERT_UNKNOWN( NumArg( UserOp ) == 4 ); - if( user_state == user_start ) - { user_index = arg[0]; - user_id = arg[1]; - user_n = arg[2]; - user_m = arg[3]; - user_atom = atomic_base::class_object(user_index); -# ifndef NDEBUG - if( user_atom == CPPAD_NULL ) - { std::string msg = - atomic_base::class_name(user_index) - + ": atomic_base function has been deleted"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - if(user_tx.size() != user_n * user_q1) - user_tx.resize(user_n * user_q1); - if(user_ty.size() != user_m * user_q1) - user_ty.resize(user_m * user_q1); - if(user_iy.size() != user_m) - user_iy.resize(user_m); - user_j = 0; - user_i = 0; - user_state = user_arg; - } - else - { CPPAD_ASSERT_UNKNOWN( user_state == user_end ); - CPPAD_ASSERT_UNKNOWN( user_index == size_t(arg[0]) ); - CPPAD_ASSERT_UNKNOWN( user_id == size_t(arg[1]) ); - CPPAD_ASSERT_UNKNOWN( user_n == size_t(arg[2]) ); - CPPAD_ASSERT_UNKNOWN( user_m == size_t(arg[3]) ); - - // call users function for this operation - user_atom->set_id(user_id); - CPPAD_ATOMIC_CALL( - p, q, user_vx, user_vy, user_tx, user_ty - ); -# ifndef NDEBUG - if( ! user_ok ) - { std::string msg = - atomic_base::class_name(user_index) - + ": atomic_base.forward: returned false"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - for(i = 0; i < user_m; i++) - if( user_iy[i] > 0 ) - for(k = p; k <= q; k++) - taylor[ user_iy[i] * J + k ] = - user_ty[ i * user_q1 + k ]; -# if CPPAD_FORWARD1SWEEP_TRACE - user_state = user_trace; -# else - user_state = user_start; -# endif - } - break; - - case UsrapOp: - // parameter argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( user_j < user_n ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - user_tx[user_j * user_q1 + 0] = parameter[ arg[0]]; - for(k = 1; k < user_q1; k++) - user_tx[user_j * user_q1 + k] = Base(0); - ++user_j; - if( user_j == user_n ) - user_state = user_ret; - break; - - case UsravOp: - // variable argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( user_j < user_n ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) <= i_var ); - for(k = 0; k < user_q1; k++) - user_tx[user_j * user_q1 + k] = taylor[ arg[0] * J + k]; - ++user_j; - if( user_j == user_n ) - user_state = user_ret; - break; - - case UsrrpOp: - // parameter result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( user_i < user_m ); - user_iy[user_i] = 0; - user_ty[user_i * user_q1 + 0] = parameter[ arg[0]]; - for(k = 1; k < p; k++) - user_ty[user_i * user_q1 + k] = Base(0); - user_i++; - if( user_i == user_m ) - user_state = user_end; - break; - - case UsrrvOp: - // variable result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( user_i < user_m ); - user_iy[user_i] = i_var; - for(k = 0; k < p; k++) - user_ty[user_i * user_q1 + k] = taylor[ i_var * J + k]; - user_i++; - if( user_i == user_m ) - user_state = user_end; - break; - // ------------------------------------------------- - - case ZmulpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_zmulpv_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case ZmulvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - forward_zmulvp_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case ZmulvvOp: - forward_zmulvv_op(p, q, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - default: - CPPAD_ASSERT_UNKNOWN(0); - } -# if CPPAD_FORWARD1SWEEP_TRACE - if( user_state == user_trace ) - { user_state = user_start; - - CPPAD_ASSERT_UNKNOWN( op == UserOp ); - CPPAD_ASSERT_UNKNOWN( NumArg(UsrrvOp) == 0 ); - for(i = 0; i < user_m; i++) if( user_iy[i] > 0 ) - { size_t i_tmp = (i_op + i) - user_m; - printOp( - std::cout, - play, - i_tmp, - user_iy[i], - UsrrvOp, - CPPAD_NULL - ); - Base* Z_tmp = taylor + user_iy[i] * J; - printOpResult( - std::cout, - q + 1, - Z_tmp, - 0, - (Base *) CPPAD_NULL - ); - std::cout << std::endl; - } - } - Base* Z_tmp = taylor + J * i_var; - const addr_t* arg_tmp = arg; - if( op == CSumOp ) - arg_tmp = arg - arg[-1] - 4; - if( op == CSkipOp ) - arg_tmp = arg - arg[-1] - 7; - if( op != UsrrvOp ) - { - printOp( - std::cout, - play, - i_op, - i_var, - op, - arg_tmp - ); - if( NumRes(op) > 0 ) printOpResult( - std::cout, - q + 1, - Z_tmp, - 0, - (Base *) CPPAD_NULL - ); - std::cout << std::endl; - } - } - std::cout << std::endl; -# else - } -# endif - CPPAD_ASSERT_UNKNOWN( user_state == user_start ); - CPPAD_ASSERT_UNKNOWN( i_var + 1 == play->num_var_rec() ); - - if( (p == 0) & (compare_change_count == 0) ) - compare_change_number = 0; - return; -} - -// preprocessor symbols that are local to this file -# undef CPPAD_FORWARD1SWEEP_TRACE -# undef CPPAD_ATOMIC_CALL - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/forward2sweep.hpp b/ct_core/include/ct/external/cppad/local/forward2sweep.hpp deleted file mode 100644 index 6ed9a4d66..000000000 --- a/ct_core/include/ct/external/cppad/local/forward2sweep.hpp +++ /dev/null @@ -1,808 +0,0 @@ -// $Id: forward2sweep.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_FORWARD2SWEEP_HPP -# define CPPAD_FORWARD2SWEEP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file forward2sweep.hpp -Compute one Taylor coefficient for each direction requested. -*/ - -/* -\def CPPAD_ATOMIC_CALL -This avoids warnings when NDEBUG is defined and user_ok is not used. -If NDEBUG is defined, this resolves to -\code - user_atom->forward -\endcode -otherwise, it respolves to -\code - user_ok = user_atom->forward -\endcode -This macro is undefined at the end of this file to facillitate its -use with a different definition in other files. -*/ -# ifdef NDEBUG -# define CPPAD_ATOMIC_CALL user_atom->forward -# else -# define CPPAD_ATOMIC_CALL user_ok = user_atom->forward -# endif - -/*! -\def CPPAD_FORWARD2SWEEP_TRACE -This value is either zero or one. -Zero is the normal operational value. -If it is one, a trace of every forward2sweep computation is printed. -*/ -# define CPPAD_FORWARD2SWEEP_TRACE 0 - -/*! -Compute multiple directions forward mode Taylor coefficients. - -\tparam Base -The type used during the forward mode computations; i.e., the corresponding -recording of operations used the type AD. - -\param q -is the order of the Taylor coefficients -that are computed during this call; -q > 0. - -\param r -is the number of Taylor coefficients -that are computed during this call. - -\param n -is the number of independent variables on the tape. - -\param numvar -is the total number of variables on the tape. -This is also equal to the number of rows in the matrix taylor; i.e., -play->num_var_rec(). - -\param play -The information stored in play -is a recording of the operations corresponding to the function -\f[ - F : {\bf R}^n \rightarrow {\bf R}^m -\f] -where \f$ n \f$ is the number of independent variables and -\f$ m \f$ is the number of dependent variables. -\n -\n -The object play is effectly constant. -The exception to this is that while palying back the tape -the object play holds information about the current location -with in the tape and this changes during palyback. - -\param J -Is the number of columns in the coefficient matrix taylor. -This must be greater than or equal one. - -\param taylor -\n -\b Input: -For i = 1 , ... , numvar-1, -taylor[ (J-1)*r*i + i + 0 ] -is the zero order Taylor coefficient corresponding to -the i-th variable and all directions. -For i = 1 , ... , numvar-1, -For k = 1 , ... , q-1, -ell = 0 , ... , r-1, -taylor[ (J-1)*r*i + i + (k-1)*r + ell + 1 ] -is the k-th order Taylor coefficient corresponding to -the i-th variabel and ell-th direction. -\n -\n -\b Input: -For i = 1 , ... , n, -ell = 0 , ... , r-1, -taylor[ (J-1)*r*i + i + (q-1)*r + ell + 1 ] -is the q-th order Taylor coefficient corresponding to -the i-th variable and ell-th direction -(these are the independent varaibles). -\n -\n -\b Output: -For i = n+1 , ... , numvar-1, -ell = 0 , ... , r-1, -taylor[ (J-1)*r*i + i + (q-1)*r + ell + 1 ] -is the q-th order Taylor coefficient corresponding to -the i-th variable and ell-th direction. - -\param cskip_op -Is a vector with size play->num_op_rec(). -If cskip_op[i] is true, the operator with index i -does not affect any of the dependent variable (given the value -of the independent variables). - -\param var_by_load_op -is a vector with size play->num_load_op_rec(). -It is the variable index corresponding to each the -load instruction. -In the case where the index is zero, -the instruction corresponds to a parameter (not variable). - -*/ - -template -void forward2sweep( - const size_t q, - const size_t r, - const size_t n, - const size_t numvar, - player* play, - const size_t J, - Base* taylor, - const bool* cskip_op, - const pod_vector& var_by_load_op -) -{ - CPPAD_ASSERT_UNKNOWN( q > 0 ); - CPPAD_ASSERT_UNKNOWN( J >= q + 1 ); - CPPAD_ASSERT_UNKNOWN( play->num_var_rec() == numvar ); - - // used to avoid compiler errors until all operators are implemented - size_t p = q; - - // op code for current instruction - OpCode op; - - // index for current instruction - size_t i_op; - - // next variables - size_t i_var; - - // operation argument indices - const addr_t* arg = CPPAD_NULL; - - // work space used by UserOp. - vector user_vx; // empty vecotor - vector user_vy; // empty vecotor - vector user_tx_one; // argument vector Taylor coefficients - vector user_tx_all; - vector user_ty_one; // result vector Taylor coefficients - vector user_ty_all; - size_t user_index = 0; // indentifier for this atomic operation - size_t user_id = 0; // user identifier for this call to operator - size_t user_i = 0; // index in result vector - size_t user_j = 0; // index in argument vector - size_t user_m = 0; // size of result vector - size_t user_n = 0; // size of arugment vector - // - atomic_base* user_atom = CPPAD_NULL; // user's atomic op calculator -# ifndef NDEBUG - bool user_ok = false; // atomic op return value -# endif - // - // next expected operator in a UserOp sequence - enum { user_start, user_arg, user_ret, user_end, user_trace } - user_state = user_start; - - // length of the parameter vector (used by CppAD assert macros) - const size_t num_par = play->num_par_rec(); - - // pointer to the beginning of the parameter vector - const Base* parameter = CPPAD_NULL; - if( num_par > 0 ) - parameter = play->GetPar(); - - // temporary indices - size_t i, j, k, ell; - - // number of orders for this user calculation - // (not needed for order zero) - const size_t user_q1 = q+1; - - // variable indices for results vector - // (done differently for order zero). - vector user_iy; - - // skip the BeginOp at the beginning of the recording - play->forward_start(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( op == BeginOp ); -# if CPPAD_FORWARD2SWEEP_TRACE - std::cout << std::endl; - CppAD::vector Z_vec(q+1); -# endif - bool more_operators = true; - while(more_operators) - { - // this op - play->forward_next(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( (i_op > n) | (op == InvOp) ); - CPPAD_ASSERT_UNKNOWN( (i_op <= n) | (op != InvOp) ); - CPPAD_ASSERT_UNKNOWN( i_op < play->num_op_rec() ); - CPPAD_ASSERT_ARG_BEFORE_RESULT(op, arg, i_var); - - // check if we are skipping this operation - while( cskip_op[i_op] ) - { if( op == CSumOp ) - { // CSumOp has a variable number of arguments - play->forward_csum(op, arg, i_op, i_var); - } - CPPAD_ASSERT_UNKNOWN( op != CSkipOp ); - // if( op == CSkipOp ) - // { // CSkip has a variable number of arguments - // play->forward_cskip(op, arg, i_op, i_var); - // } - play->forward_next(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( i_op < play->num_op_rec() ); - } - - // action depends on the operator - switch( op ) - { - case AbsOp: - forward_abs_op_dir(q, r, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case AddvvOp: - forward_addvv_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case AddpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_addpv_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case AcosOp: - // sqrt(1 - x * x), acos(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_acos_op_dir(q, r, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AcoshOp: - // sqrt(x * x - 1), acosh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_acosh_op_dir(q, r, i_var, arg[0], J, taylor); - break; -# endif - // ------------------------------------------------- - - case AsinOp: - // sqrt(1 - x * x), asin(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_asin_op_dir(q, r, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AsinhOp: - // sqrt(1 + x * x), asinh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_asinh_op_dir(q, r, i_var, arg[0], J, taylor); - break; -# endif - // ------------------------------------------------- - - case AtanOp: - // 1 + x * x, atan(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_atan_op_dir(q, r, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AtanhOp: - // 1 - x * x, atanh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_atanh_op_dir(q, r, i_var, arg[0], J, taylor); - break; -# endif - // ------------------------------------------------- - - case CExpOp: - forward_cond_op_dir( - q, r, i_var, arg, num_par, parameter, J, taylor - ); - break; - // --------------------------------------------------- - - case CosOp: - // sin(x), cos(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_cos_op_dir(q, r, i_var, arg[0], J, taylor); - break; - // --------------------------------------------------- - - case CoshOp: - // sinh(x), cosh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_cosh_op_dir(q, r, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case CSkipOp: - // CSkipOp has a variable number of arguments and - // forward_next thinks it has no arguments. - // we must inform forward_next of this special case. - play->forward_cskip(op, arg, i_op, i_var); - break; - // ------------------------------------------------- - - case CSumOp: - // CSumOp has a variable number of arguments and - // forward_next thinks it has no arguments. - // we must inform forward_next of this special case. - forward_csum_op_dir( - q, r, i_var, arg, num_par, parameter, J, taylor - ); - play->forward_csum(op, arg, i_op, i_var); - break; - // ------------------------------------------------- - - case DisOp: - forward_dis_op(p, q, r, i_var, arg, J, taylor); - break; - // ------------------------------------------------- - - case DivvvOp: - forward_divvv_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case DivpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_divpv_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case DivvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - forward_divvp_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case EndOp: - // needed for sparse_jacobian test - CPPAD_ASSERT_NARG_NRES(op, 0, 0); - more_operators = false; - break; - // ------------------------------------------------- - - case ExpOp: - forward_exp_op_dir(q, r, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case Expm1Op: - forward_expm1_op_dir(q, r, i_var, arg[0], J, taylor); - break; -# endif - // ------------------------------------------------- - - case InvOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 1); - break; - // ------------------------------------------------- - - case LdpOp: - case LdvOp: - forward_load_op( - play, - op, - p, - q, - r, - J, - i_var, - arg, - var_by_load_op.data(), - taylor - ); - break; - // --------------------------------------------------- - - case EqpvOp: - case EqvvOp: - case LtpvOp: - case LtvpOp: - case LtvvOp: - case LepvOp: - case LevpOp: - case LevvOp: - case NepvOp: - case NevvOp: - CPPAD_ASSERT_UNKNOWN(q > 0 ); - break; - // ------------------------------------------------- - - case LogOp: - forward_log_op_dir(q, r, i_var, arg[0], J, taylor); - break; - // --------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case Log1pOp: - forward_log1p_op_dir(q, r, i_var, arg[0], J, taylor); - break; -# endif - // --------------------------------------------------- - - case MulpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_mulpv_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case MulvvOp: - forward_mulvv_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case ParOp: - k = i_var*(J-1)*r + i_var + (q-1)*r + 1; - for(ell = 0; ell < r; ell++) - taylor[k + ell] = Base(0); - break; - // ------------------------------------------------- - - case PowpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_powpv_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case PowvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - forward_powvp_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case PowvvOp: - forward_powvv_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case PriOp: - CPPAD_ASSERT_UNKNOWN(q > 0); - break; - // ------------------------------------------------- - - case SignOp: - // sign(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_sign_op_dir(q, r, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case SinOp: - // cos(x), sin(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_sin_op_dir(q, r, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case SinhOp: - // cosh(x), sinh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_sinh_op_dir(q, r, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case SqrtOp: - forward_sqrt_op_dir(q, r, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case StppOp: - case StpvOp: - case StvpOp: - case StvvOp: - CPPAD_ASSERT_UNKNOWN(q > 0 ); - break; - // ------------------------------------------------- - - case SubvvOp: - forward_subvv_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case SubpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_subpv_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case SubvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - forward_subvp_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case TanOp: - // tan(x)^2, tan(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_tan_op_dir(q, r, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case TanhOp: - // tanh(x)^2, tanh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - forward_tanh_op_dir(q, r, i_var, arg[0], J, taylor); - break; - // ------------------------------------------------- - - case UserOp: - // start or end an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( NumRes( UserOp ) == 0 ); - CPPAD_ASSERT_UNKNOWN( NumArg( UserOp ) == 4 ); - if( user_state == user_start ) - { user_index = arg[0]; - user_id = arg[1]; - user_n = arg[2]; - user_m = arg[3]; - user_atom = atomic_base::class_object(user_index); -# ifndef NDEBUG - if( user_atom == CPPAD_NULL ) - { std::string msg = - atomic_base::class_name(user_index) - + ": atomic_base function has been deleted"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - if(user_tx_one.size() != user_n * user_q1) - user_tx_one.resize(user_n * user_q1); - if( user_tx_all.size() != user_n * (q * r + 1) ) - user_tx_all.resize(user_n * (q * r + 1)); - // - if(user_ty_one.size() != user_m * user_q1) - user_ty_one.resize(user_m * user_q1); - if( user_ty_all.size() != user_m * (q * r + 1) ) - user_ty_all.resize(user_m * (q * r + 1)); - // - if(user_iy.size() != user_m) - user_iy.resize(user_m); - user_j = 0; - user_i = 0; - user_state = user_arg; - } - else - { CPPAD_ASSERT_UNKNOWN( user_state == user_end ); - CPPAD_ASSERT_UNKNOWN( user_index == size_t(arg[0]) ); - CPPAD_ASSERT_UNKNOWN( user_id == size_t(arg[1]) ); - CPPAD_ASSERT_UNKNOWN( user_n == size_t(arg[2]) ); - CPPAD_ASSERT_UNKNOWN( user_m == size_t(arg[3]) ); - - // call users function for this operation - user_atom->set_id(user_id); - for(ell = 0; ell < r; ell++) - { // set user_tx - for(j = 0; j < user_n; j++) - { size_t j_all = j * (q * r + 1); - size_t j_one = j * user_q1; - user_tx_one[j_one+0] = user_tx_all[j_all+0]; - for(k = 1; k < user_q1; k++) - { size_t k_all = j_all + (k-1)*r+1+ell; - size_t k_one = j_one + k; - user_tx_one[k_one] = user_tx_all[k_all]; - } - } - // set user_ty - for(i = 0; i < user_m; i++) - { size_t i_all = i * (q * r + 1); - size_t i_one = i * user_q1; - user_ty_one[i_one+0] = user_ty_all[i_all+0]; - for(k = 1; k < q; k++) - { size_t k_all = i_all + (k-1)*r+1+ell; - size_t k_one = i_one + k; - user_ty_one[k_one] = user_ty_all[k_all]; - } - } - CPPAD_ATOMIC_CALL( - q, q, user_vx, user_vy, user_tx_one, user_ty_one - ); -# ifndef NDEBUG - if( ! user_ok ) - { std::string msg = - atomic_base::class_name(user_index) - + ": atomic_base.forward: returned false"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - for(i = 0; i < user_m; i++) - { if( user_iy[i] > 0 ) - { size_t i_taylor = user_iy[i]*((J-1)*r+1); - size_t q_taylor = i_taylor + (q-1)*r+1+ell; - size_t q_one = i * user_q1 + q; - taylor[q_taylor] = user_ty_one[q_one]; - } - } - } -# if CPPAD_FORWARD2SWEEP_TRACE - user_state = user_trace; -# else - user_state = user_start; -# endif - } - break; - - case UsrapOp: - // parameter argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( user_j < user_n ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - user_tx_all[user_j*(q*r+1) + 0] = parameter[ arg[0]]; - for(ell = 0; ell < r; ell++) - for(k = 1; k < user_q1; k++) - user_tx_all[user_j*(q*r+1) + (k-1)*r+1+ell] = Base(0); - ++user_j; - if( user_j == user_n ) - user_state = user_ret; - break; - - case UsravOp: - // variable argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( user_j < user_n ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) <= i_var ); - user_tx_all[user_j*(q*r+1)+0] = taylor[arg[0]*((J-1)*r+1)+0]; - for(ell = 0; ell < r; ell++) - { for(k = 1; k < user_q1; k++) - { user_tx_all[user_j*(q*r+1) + (k-1)*r+1+ell] = - taylor[arg[0]*((J-1)*r+1) + (k-1)*r+1+ell]; - } - } - ++user_j; - if( user_j == user_n ) - user_state = user_ret; - break; - - case UsrrpOp: - // parameter result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( user_i < user_m ); - user_iy[user_i] = 0; - user_ty_all[user_i*(q*r+1) + 0] = parameter[ arg[0]]; - for(ell = 0; ell < r; ell++) - for(k = 1; k < user_q1; k++) - user_ty_all[user_i*(q*r+1) + (k-1)*r+1+ell] = Base(0); - user_i++; - if( user_i == user_m ) - user_state = user_end; - break; - - case UsrrvOp: - // variable result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( user_i < user_m ); - user_iy[user_i] = i_var; - user_ty_all[user_i*(q*r+1)+0] = taylor[i_var*((J-1)*r+1)+0]; - for(ell = 0; ell < r; ell++) - { for(k = 1; k < user_q1; k++) - { user_ty_all[user_i*(q*r+1) + (k-1)*r+1+ell] = - taylor[i_var*((J-1)*r+1) + (k-1)*r+1+ell]; - } - } - user_i++; - if( user_i == user_m ) - user_state = user_end; - break; - // ------------------------------------------------- - - case ZmulpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - forward_zmulpv_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case ZmulvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - forward_zmulvp_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - case ZmulvvOp: - forward_zmulvv_op_dir(q, r, i_var, arg, parameter, J, taylor); - break; - // ------------------------------------------------- - - default: - CPPAD_ASSERT_UNKNOWN(0); - } -# if CPPAD_FORWARD2SWEEP_TRACE - if( user_state == user_trace ) - { user_state = user_start; - CPPAD_ASSERT_UNKNOWN( op == UserOp ); - CPPAD_ASSERT_UNKNOWN( NumArg(UsrrvOp) == 0 ); - for(i = 0; i < user_m; i++) if( user_iy[i] > 0 ) - { size_t i_tmp = (i_op + i) - user_m; - printOp( - std::cout, - play, - i_tmp, - user_iy[i], - UsrrvOp, - CPPAD_NULL - ); - Base* Z_tmp = taylor + user_iy[i]*((J-1) * r + 1); - { Z_vec[0] = Z_tmp[0]; - for(ell = 0; ell < r; ell++) - { std::cout << std::endl << " "; - for(size_t p_tmp = 1; p_tmp <= q; p_tmp++) - Z_vec[p_tmp] = Z_tmp[(p_tmp-1)*r+ell+1]; - printOpResult( - std::cout, - q + 1, - Z_vec.data(), - 0, - (Base *) CPPAD_NULL - ); - } - } - std::cout << std::endl; - } - } - const addr_t* arg_tmp = arg; - if( op == CSumOp ) - arg_tmp = arg - arg[-1] - 4; - if( op == CSkipOp ) - arg_tmp = arg - arg[-1] - 7; - if( op != UsrrvOp ) - { printOp( - std::cout, - play, - i_op, - i_var, - op, - arg_tmp - ); - Base* Z_tmp = CPPAD_NULL; - if( op == UsravOp ) - Z_tmp = taylor + arg[0]*((J-1) * r + 1); - else if( NumRes(op) > 0 ) - Z_tmp = taylor + i_var*((J-1)*r + 1); - if( Z_tmp != CPPAD_NULL ) - { Z_vec[0] = Z_tmp[0]; - for(ell = 0; ell < r; ell++) - { std::cout << std::endl << " "; - for(size_t p_tmp = 1; p_tmp <= q; p_tmp++) - Z_vec[p_tmp] = Z_tmp[ (p_tmp-1)*r + ell + 1]; - printOpResult( - std::cout, - q + 1, - Z_vec.data(), - 0, - (Base *) CPPAD_NULL - ); - } - } - std::cout << std::endl; - } - } - std::cout << std::endl; -# else - } -# endif - CPPAD_ASSERT_UNKNOWN( user_state == user_start ); - CPPAD_ASSERT_UNKNOWN( i_var + 1 == play->num_var_rec() ); - - return; -} - -// preprocessor symbols that are local to this file -# undef CPPAD_FORWARD2SWEEP_TRACE -# undef CPPAD_ATOMIC_CALL - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/fun_check.hpp b/ct_core/include/ct/external/cppad/local/fun_check.hpp deleted file mode 100644 index c91deedb0..000000000 --- a/ct_core/include/ct/external/cppad/local/fun_check.hpp +++ /dev/null @@ -1,211 +0,0 @@ -// $Id: fun_check.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_FUN_CHECK_HPP -# define CPPAD_FUN_CHECK_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin FunCheck$$ -$spell - exp - bool - const - Taylor -$$ - - -$section Check an ADFun Sequence of Operations$$ - -$head Syntax$$ -$icode%ok% = FunCheck(%f%, %g%, %x%, %r%, %a%)%$$ -$pre -$$ -$bold See Also$$ -$cref CompareChange$$ - - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -We use $latex G : B^n \rightarrow B^m$$ to denote the -function corresponding to the C++ function object $icode g$$. -This routine check if -$latex \[ - F(x) = G(x) -\]$$ -If $latex F(x) \neq G(x)$$, the -$cref/operation sequence/glossary/Operation/Sequence/$$ -corresponding to $icode f$$ does not represents the algorithm used -by $icode g$$ to calculate values for $latex G$$ -(see $cref/Discussion/FunCheck/Discussion/$$ below). - -$head f$$ -The $code FunCheck$$ argument $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/Forward/FunCheck/FunCheck Uses Forward/$$ below). - -$head g$$ -The $code FunCheck$$ argument $icode g$$ has prototype -$codei% - %Fun% &%g% -%$$ -($icode Fun$$ is defined the properties of $icode g$$). -The C++ function object $icode g$$ supports the syntax -$codei% - %y% = %g%(%x%) -%$$ -which computes $latex y = G(x)$$. - -$subhead x$$ -The $icode g$$ argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -(see $cref/Vector/FunCheck/Vector/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. - -$head y$$ -The $icode g$$ result $icode y$$ has prototype -$codei% - %Vector% %y% -%$$ -and its value is $latex G(x)$$. -The size of $icode y$$ -is equal to $icode m$$, the dimension of the -$cref/range/seq_property/Range/$$ space for $icode f$$. - -$head x$$ -The $code FunCheck$$ argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -This specifies that point at which to compare the values -calculated by $icode f$$ and $icode G$$. - -$head r$$ -The $code FunCheck$$ argument $icode r$$ has prototype -$codei% - const %Base% &%r% -%$$ -It specifies the relative error the element by element -comparison of the value of $latex F(x)$$ and $latex G(x)$$. - -$head a$$ -The $code FunCheck$$ argument $icode a$$ has prototype -$codei% - const %Base% &%a% -%$$ -It specifies the absolute error the element by element -comparison of the value of $latex F(x)$$ and $latex G(x)$$. - -$head ok$$ -The $code FunCheck$$ result $icode ok$$ has prototype -$codei% - bool %ok% -%$$ -It is true, if for $latex i = 0 , \ldots , m-1$$ -either the relative error bound is satisfied -$latex \[ -| F_i (x) - G_i (x) | -\leq -r ( | F_i (x) | + | G_i (x) | ) -\] $$ -or the absolute error bound is satisfied -$latex \[ - | F_i (x) - G_i (x) | \leq a -\] $$ -It is false if for some $latex (i, j)$$ neither -of these bounds is satisfied. - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Base$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head FunCheck Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After $code FunCheck$$, -the previous calls to $cref Forward$$ are undefined. - -$head Discussion$$ -Suppose that the algorithm corresponding to $icode g$$ contains -$codei% - if( %x% >= 0 ) - %y% = exp(%x%) - else %y% = exp(-%x%) -%$$ -where $icode x$$ and $icode y$$ are $codei%AD%$$ objects. -It follows that the -AD of $code double$$ $cref/operation sequence/glossary/Operation/Sequence/$$ -depends on the value of $icode x$$. -If the sequence of operations stored in $icode f$$ corresponds to -$icode g$$ with $latex x \geq 0$$, -the function values computed using $icode f$$ when $latex x < 0$$ -will not agree with the function values computed by $latex g$$. -This is because the operation sequence corresponding to $icode g$$ changed -(and hence the object $icode f$$ does not represent the function -$latex G$$ for this value of $icode x$$). -In this case, you probably want to re-tape the calculations -performed by $icode g$$ with the -$cref/independent variables/glossary/Tape/Independent Variable/$$ -equal to the values in $icode x$$ -(so AD operation sequence properly represents the algorithm -for this value of independent variables). - - -$head Example$$ -$children% - example/fun_check.cpp -%$$ -The file -$cref fun_check.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end ---------------------------------------------------------------------------- -*/ - -namespace CppAD { - template - bool FunCheck( - ADFun &f , - Fun &g , - const Vector &x , - const Base &r , - const Base &a ) - { bool ok = true; - - size_t m = f.Range(); - Vector yf = f.Forward(0, x); - Vector yg = g(x); - - size_t i; - for(i = 0; i < m; i++) - ok &= NearEqual(yf[i], yg[i], r, a); - return ok; - } -} - -# endif diff --git a/ct_core/include/ct/external/cppad/local/fun_construct.hpp b/ct_core/include/ct/external/cppad/local/fun_construct.hpp deleted file mode 100644 index 05c19cd8c..000000000 --- a/ct_core/include/ct/external/cppad/local/fun_construct.hpp +++ /dev/null @@ -1,489 +0,0 @@ -// $Id: fun_construct.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_FUN_CONSTRUCT_HPP -# define CPPAD_FUN_CONSTRUCT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin FunConstruct$$ -$spell - alloc - num - Jac - bool - taylor - var - ADvector - const - Jacobian -$$ - -$spell -$$ - -$section Construct an ADFun Object and Stop Recording$$ -$mindex tape$$ - - -$head Syntax$$ -$codei%ADFun<%Base%> %f%, %g% -%$$ -$codei%ADFun<%Base%> %f%(%x%, %y%) -%$$ -$icode%g% = %f% -%$$ - - -$head Purpose$$ -The $codei%AD<%Base%>%$$ object $icode f$$ can -store an AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. -It can then be used to calculate derivatives of the corresponding -$cref/AD function/glossary/AD Function/$$ -$latex \[ - F : B^n \rightarrow B^m -\] $$ -where $latex B$$ is the space corresponding to objects of type $icode Base$$. - -$head x$$ -If the argument $icode x$$ is present, it has prototype -$codei% - const %VectorAD% &%x% -%$$ -It must be the vector argument in the previous call to -$cref Independent$$. -Neither its size, or any of its values, are allowed to change -between calling -$codei% - Independent(%x%) -%$$ -and -$codei% - ADFun<%Base%> %f%(%x%, %y%) -%$$ - -$head y$$ -If the argument $icode y$$ is present, it has prototype -$codei% - const %VectorAD% &%y% -%$$ -The sequence of operations that map $icode x$$ -to $icode y$$ are stored in the ADFun object $icode f$$. - -$head VectorAD$$ -The type $icode VectorAD$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$codei%AD<%Base%>%$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Default Constructor$$ -The default constructor -$codei% - ADFun<%Base%> %f% -%$$ -creates an -$codei%AD<%Base%>%$$ object with no corresponding operation sequence; i.e., -$codei% - %f%.size_var() -%$$ -returns the value zero (see $cref/size_var/seq_property/size_var/$$). - -$head Sequence Constructor$$ -The sequence constructor -$codei% - ADFun<%Base%> %f%(%x%, %y%) -%$$ -creates the $codei%AD<%Base%>%$$ object $icode f$$, -stops the recording of AD of $icode Base$$ operations -corresponding to the call -$codei% - Independent(%x%) -%$$ -and stores the corresponding operation sequence in the object $icode f$$. -It then stores the zero order Taylor coefficients -(corresponding to the value of $icode x$$) in $icode f$$. -This is equivalent to the following steps using the default constructor: - -$list number$$ -Create $icode f$$ with the default constructor -$codei% - ADFun<%Base%> %f%; -%$$ -$lnext -Stop the tape and storing the operation sequence using -$codei% - %f%.Dependent(%x%, %y%); -%$$ -(see $cref Dependent$$). -$lnext -Calculate the zero order Taylor coefficients for all -the variables in the operation sequence using -$codei% - %f%.Forward(%p%, %x_p%) -%$$ -with $icode p$$ equal to zero and the elements of $icode x_p$$ -equal to the corresponding elements of $icode x$$ -(see $cref Forward$$). -$lend - -$head Copy Constructor$$ -It is an error to attempt to use the $codei%ADFun<%Base%>%$$ copy constructor; -i.e., the following syntax is not allowed: -$codei% - ADFun<%Base%> %g%(%f%) -%$$ -where $icode f$$ is an $codei%ADFun<%Base%>%$$ object. -Use its $cref/default constructor/FunConstruct/Default Constructor/$$ instead -and its assignment operator. - -$head Assignment Operator$$ -The $codei%ADFun<%Base%>%$$ assignment operation -$codei% - %g% = %f% -%$$ -makes a copy of the operation sequence currently stored in $icode f$$ -in the object $icode g$$. -The object $icode f$$ is not affected by this operation and -can be $code const$$. -All of information (state) stored in $icode f$$ is copied to $icode g$$ -and any information originally in $icode g$$ is lost. - -$subhead Taylor Coefficients$$ -The Taylor coefficient information currently stored in $icode f$$ -(computed by $cref/f.Forward/Forward/$$) is -copied to $icode g$$. -Hence, directly after this operation -$codei% - %g%.size_order() == %f%.size_order() -%$$ - -$subhead Sparsity Patterns$$ -The forward Jacobian sparsity pattern currently stored in $icode f$$ -(computed by $cref/f.ForSparseJac/ForSparseJac/$$) is -copied to $icode g$$. -Hence, directly after this operation -$codei% - %g%.size_forward_bool() == %f%.size_forward_bool() - %g%.size_forward_set() == %f%.size_forward_set() -%$$ - -$head Parallel Mode$$ -The call to $code Independent$$, -and the corresponding call to -$codei% - ADFun<%Base%> %f%( %x%, %y%) -%$$ -or -$codei% - %f%.Dependent( %x%, %y%) -%$$ -or $cref abort_recording$$, -must be preformed by the same thread; i.e., -$cref/thread_alloc::thread_num/ta_thread_num/$$ must be the same. - -$head Example$$ - -$subhead Sequence Constructor$$ -The file -$cref independent.cpp$$ -contains an example and test of the sequence constructor. -It returns true if it succeeds and false otherwise. - -$subhead Default Constructor$$ -The files -$cref fun_check.cpp$$ -and -$cref hes_lagrangian.cpp$$ -contain an examples and tests using the default constructor. -They return true if they succeed and false otherwise. - -$children% - example/fun_assign.cpp -%$$ -$subhead Assignment Operator$$ -The file -$cref fun_assign.cpp$$ -contains an example and test of the $codei%ADFun<%Base%>%$$ -assignment operator. -It returns true if it succeeds and false otherwise. - -$end ----------------------------------------------------------------------------- -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file fun_construct.hpp -ADFun function constructors and assignment operator. -*/ - -/*! -ADFun default constructor - -The C++ syntax for this operation is -\verbatim - ADFun f -\endverbatim -An empty ADFun object is created. -The Dependent member function, -or the ADFun assingment operator, -can then be used to put an operation sequence in this ADFun object. - -\tparam Base -is the base for the recording that can be stored in this ADFun object; -i.e., operation sequences that were recorded using the type \c AD. -*/ -template -ADFun::ADFun(void) : -has_been_optimized_(false), -check_for_nan_(true) , -compare_change_count_(1), -compare_change_number_(0), -compare_change_op_index_(0), -num_var_tape_(0) -{ } - -/*! -ADFun assignment operator - -The C++ syntax for this operation is -\verbatim - g = f -\endverbatim -where \c g and \c f are ADFun ADFun objects. -A copy of the the operation sequence currently stored in \c f -is placed in this ADFun object (called \c g above). -Any information currently stored in this ADFun object is lost. - -\tparam Base -is the base for the recording that can be stored in this ADFun object; -i.e., operation sequences that were recorded using the type \c AD. - -\param f -ADFun object containing the operation sequence to be copied. -*/ -template -void ADFun::operator=(const ADFun& f) -{ size_t m = f.Range(); - size_t n = f.Domain(); - size_t i; - - // go through member variables in ad_fun.hpp order - // - // size_t objects - has_been_optimized_ = f.has_been_optimized_; - check_for_nan_ = f.check_for_nan_; - compare_change_count_ = f.compare_change_count_; - compare_change_number_ = f.compare_change_number_; - compare_change_op_index_ = f.compare_change_op_index_; - num_order_taylor_ = f.num_order_taylor_; - cap_order_taylor_ = f.cap_order_taylor_; - num_direction_taylor_ = f.num_direction_taylor_; - num_var_tape_ = f.num_var_tape_; - // - // CppAD::vector objects - ind_taddr_.resize(n); - ind_taddr_ = f.ind_taddr_; - dep_taddr_.resize(m); - dep_taddr_ = f.dep_taddr_; - dep_parameter_.resize(m); - dep_parameter_ = f.dep_parameter_; - // - // pod_vector objects - taylor_ = f.taylor_; - cskip_op_ = f.cskip_op_; - load_op_ = f.load_op_; - // - // player - play_ = f.play_; - // - // sparse_pack - for_jac_sparse_pack_.resize(0, 0); - size_t n_set = f.for_jac_sparse_pack_.n_set(); - size_t end = f.for_jac_sparse_pack_.end(); - if( n_set > 0 ) - { CPPAD_ASSERT_UNKNOWN( n_set == num_var_tape_ ); - CPPAD_ASSERT_UNKNOWN( f.for_jac_sparse_set_.n_set() == 0 ); - for_jac_sparse_pack_.resize(n_set, end); - for(i = 0; i < num_var_tape_ ; i++) - { for_jac_sparse_pack_.assignment( - i , - i , - f.for_jac_sparse_pack_ - ); - } - } - // - // sparse_set - for_jac_sparse_set_.resize(0, 0); - n_set = f.for_jac_sparse_set_.n_set(); - end = f.for_jac_sparse_set_.end(); - if( n_set > 0 ) - { CPPAD_ASSERT_UNKNOWN( n_set == num_var_tape_ ); - CPPAD_ASSERT_UNKNOWN( f.for_jac_sparse_pack_.n_set() == 0 ); - for_jac_sparse_set_.resize(n_set, end); - for(i = 0; i < num_var_tape_; i++) - { for_jac_sparse_set_.assignment( - i , - i , - f.for_jac_sparse_set_ - ); - } - } -} - -/*! -ADFun constructor from an operation sequence. - -The C++ syntax for this operation is -\verbatim - ADFun f(x, y) -\endverbatim -The operation sequence that started with the previous call -\c Independent(x), and that ends with this operation, is stored -in this \c ADFun object \c f. - -\tparam Base -is the base for the recording that will be stored in the object \c f; -i.e., the operations were recorded using the type \c AD. - -\tparam VectorAD -is a simple vector class with elements of typea \c AD. - -\param x -is the independent variable vector for this ADFun object. -The domain dimension of this object will be the size of \a x. - -\param y -is the dependent variable vector for this ADFun object. -The range dimension of this object will be the size of \a y. - -\par Taylor Coefficients -A zero order forward mode sweep is done, -and if NDEBUG is not defined the resulting values for the -depenedent variables are checked against the values in \a y. -Thus, the zero order Taylor coefficients -corresponding to the value of the \a x vector -are stored in this ADFun object. -*/ -template -template -ADFun::ADFun(const VectorAD &x, const VectorAD &y) -{ - CPPAD_ASSERT_KNOWN( - x.size() > 0, - "ADFun: independent variable vector has size zero." - ); - CPPAD_ASSERT_KNOWN( - Variable(x[0]), - "ADFun: independent variable vector has been changed." - ); - ADTape* tape = AD::tape_ptr(x[0].tape_id_); - CPPAD_ASSERT_KNOWN( - tape->size_independent_ == size_t ( x.size() ), - "ADFun: independent variable vector has been changed." - ); - size_t j, n = x.size(); -# ifndef NDEBUG - size_t i, m = y.size(); - for(j = 0; j < n; j++) - { CPPAD_ASSERT_KNOWN( - size_t(x[j].taddr_) == (j+1), - "ADFun: independent variable vector has been changed." - ); - CPPAD_ASSERT_KNOWN( - x[j].tape_id_ == x[0].tape_id_, - "ADFun: independent variable vector has been changed." - ); - } - for(i = 0; i < m; i++) - { CPPAD_ASSERT_KNOWN( - CppAD::Parameter( y[i] ) | (y[i].tape_id_ == x[0].tape_id_) , - "ADFun: dependent vector contains variables for" - "\na different tape than the independent variables." - ); - } -# endif - - // stop the tape and store the operation sequence - Dependent(tape, y); - - - // ad_fun.hpp member values not set by dependent - check_for_nan_ = true; - - // allocate memory for one zero order taylor_ coefficient - CPPAD_ASSERT_UNKNOWN( num_order_taylor_ == 0 ); - CPPAD_ASSERT_UNKNOWN( num_direction_taylor_ == 0 ); - size_t c = 1; - size_t r = 1; - capacity_order(c, r); - CPPAD_ASSERT_UNKNOWN( cap_order_taylor_ == c ); - CPPAD_ASSERT_UNKNOWN( num_direction_taylor_ == r ); - - // set zero order coefficients corresponding to indpendent variables - CPPAD_ASSERT_UNKNOWN( n == ind_taddr_.size() ); - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] == (j+1) ); - CPPAD_ASSERT_UNKNOWN( size_t(x[j].taddr_) == (j+1) ); - taylor_[ ind_taddr_[j] ] = x[j].value_; - } - - // use independent variable values to fill in values for others - CPPAD_ASSERT_UNKNOWN( cskip_op_.size() == play_.num_op_rec() ); - CPPAD_ASSERT_UNKNOWN( load_op_.size() == play_.num_load_op_rec() ); - forward0sweep(std::cout, false, - n, num_var_tape_, &play_, cap_order_taylor_, taylor_.data(), - cskip_op_.data(), load_op_, - compare_change_count_, - compare_change_number_, - compare_change_op_index_ - ); - CPPAD_ASSERT_UNKNOWN( compare_change_count_ == 1 ); - CPPAD_ASSERT_UNKNOWN( compare_change_number_ == 0 ); - CPPAD_ASSERT_UNKNOWN( compare_change_op_index_ == 0 ); - - // now set the number of orders stored - num_order_taylor_ = 1; - -# ifndef NDEBUG - // on MS Visual Studio 2012, CppAD required in front of isnan ? - for(i = 0; i < m; i++) - if( taylor_[dep_taddr_[i]] != y[i].value_ || CppAD::isnan( y[i].value_ ) ) - { using std::endl; - std::ostringstream buf; - buf << "A dependent variable value is not equal to " - << "its tape evaluation value," << endl - << "perhaps it is nan." << endl - << "Dependent variable value = " - << y[i].value_ << endl - << "Tape evaluation value = " - << taylor_[dep_taddr_[i]] << endl - << "Difference = " - << y[i].value_ - taylor_[dep_taddr_[i]] << endl - ; - // buf.str() returns a string object with a copy of the current - // contents in the stream buffer. - std::string msg_str = buf.str(); - // msg_str.c_str() returns a pointer to the c-string - // representation of the string object's value. - const char* msg_char_star = msg_str.c_str(); - CPPAD_ASSERT_KNOWN( - 0, - msg_char_star - ); - } -# endif -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/fun_eval.hpp b/ct_core/include/ct/external/cppad/local/fun_eval.hpp deleted file mode 100644 index 3929bbb88..000000000 --- a/ct_core/include/ct/external/cppad/local/fun_eval.hpp +++ /dev/null @@ -1,37 +0,0 @@ -// $Id: fun_eval.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_FUN_EVAL_HPP -# define CPPAD_FUN_EVAL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin FunEval$$ -$spell -$$ - - -$section Evaluate ADFun Functions, Derivatives, and Sparsity Patterns$$ - -$childtable% - omh/forward/forward.omh% - omh/reverse/reverse.omh% - cppad/local/sparse.hpp -%$$ - -$end -*/ - -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/local/hash_code.hpp b/ct_core/include/ct/external/cppad/local/hash_code.hpp deleted file mode 100644 index 37b33e18b..000000000 --- a/ct_core/include/ct/external/cppad/local/hash_code.hpp +++ /dev/null @@ -1,253 +0,0 @@ -// $Id: hash_code.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_HASH_CODE_HPP -# define CPPAD_HASH_CODE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file hash_code.hpp -CppAD hashing utility. -*/ - -/*! -\def CPPAD_HASH_TABLE_SIZE -the codes retruned by hash_code are between zero and CPPAD_HASH_TABLE_SIZE -minus one. -*/ -# define CPPAD_HASH_TABLE_SIZE 10000 - -/*! -General purpose hash code for an arbitrary value. - -\tparam Value -is the type of the argument being hash coded. -It should be a plain old data class; i.e., -the values included in the equality operator in the object and -not pointed to by the object. - -\param value -the value that we are generating a hash code for. - -\return -is a hash code that is between zero and CPPAD_HASH_TABLE_SIZE - 1. - -\par Checked Assertions -\li \c std::numeric_limits::max() >= CPPAD_HASH_TABLE_SIZE -\li \c sizeof(value) is even -\li \c sizeof(unsigned short) == 2 -*/ - -template -unsigned short hash_code(const Value& value) -{ CPPAD_ASSERT_UNKNOWN( - std::numeric_limits::max() - >= - CPPAD_HASH_TABLE_SIZE - ); - CPPAD_ASSERT_UNKNOWN( sizeof(unsigned short) == 2 ); - CPPAD_ASSERT_UNKNOWN( sizeof(value) % 2 == 0 ); - # - const unsigned short* v - = reinterpret_cast(& value); - # - size_t i = sizeof(value) / 2 - 1; - # - unsigned short code = v[i]; - # - while(i--) - code += v[i]; - - return code % CPPAD_HASH_TABLE_SIZE; -} - -/*! -Specialized hash code for a CppAD operator and its arguments. - -\param op -is the operator that we are computing a hash code for. -If it is not one of the following operartors, the operator is not -hash coded and zero is returned: - -\li unary operators: -AbsOp, AcosOp, AcoshOp, AsinOp, AsinhOp, AtanOp, AtanhOp, CosOp, CoshOp -ExpOp, Expm1Op, LogOp, Log1pOp, SinOp, SinhOp, SqrtOp, TanOp, TanhOp - -\li binary operators where first argument is a parameter: -AddpvOp, DivpvOp, MulpvOp, PowpvOp, SubpvOp, ZmulpvOp - -\li binary operators where second argument is a parameter: -DivvpOp, PowvpOp, SubvpOp, Zmulvp - -\li binary operators where first is an index and second is a variable: -DisOp - -\li binary operators where both arguments are variables: -AddvvOp, DivvvOp, MulvvOp, PowvvOp, SubvvOp, ZmulvvOp - -\param arg -is a vector of length \c NumArg(op) or 2 (which ever is smaller), -containing the corresponding argument indices for this operator. - -\param npar -is the number of parameters corresponding to this operation sequence. - -\param par -is a vector of length \a npar containing the parameters -for this operation sequence; i.e., -given a parameter index of \c i, the corresponding parameter value is -\a par[i]. - - -\return -is a hash code that is between zero and CPPAD_HASH_TABLE_SIZE - 1. - -\par Checked Assertions -\c op must be one of the operators specified above. In addition, -\li \c std::numeric_limits::max() >= CPPAD_HASH_TABLE_SIZE -\li \c sizeof(size_t) is even -\li \c sizeof(Base) is even -\li \c sizeof(unsigned short) == 2 -\li \c size_t(op) < size_t(NumberOp) <= CPPAD_HASH_TABLE_SIZE -\li if the j-th argument for this operation is a parameter, arg[j] < npar. -*/ - -template -unsigned short hash_code( - OpCode op , - const addr_t* arg , - size_t npar , - const Base* par ) -{ CPPAD_ASSERT_UNKNOWN( - std::numeric_limits::max() - >= - CPPAD_HASH_TABLE_SIZE - ); - CPPAD_ASSERT_UNKNOWN( size_t (op) < size_t(NumberOp) ); - CPPAD_ASSERT_UNKNOWN( sizeof(unsigned short) == 2 ); - CPPAD_ASSERT_UNKNOWN( sizeof(addr_t) % 2 == 0 ); - CPPAD_ASSERT_UNKNOWN( sizeof(Base) % 2 == 0 ); - unsigned short op_fac = static_cast ( - CPPAD_HASH_TABLE_SIZE / static_cast(NumberOp) - ); - CPPAD_ASSERT_UNKNOWN( op_fac > 0 ); - - // number of shorts per addr_t value - size_t short_addr_t = sizeof(addr_t) / 2; - - // number of shorts per Base value - size_t short_base = sizeof(Base) / 2; - - // initialize with value that separates operators as much as possible - unsigned short code = static_cast( - static_cast(op) * op_fac - ); - - // now code in the operands - size_t i; - const unsigned short* v; - - // first argument - switch(op) - { // Binary operators where first arugment is a parameter. - // Code parameters by value instead of - // by index for two reasons. One, it gives better separation. - // Two, different indices can be same parameter value. - case AddpvOp: - case DivpvOp: - case MulpvOp: - case PowpvOp: - case SubpvOp: - case ZmulpvOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 2 ); - v = reinterpret_cast(par + arg[0]); - i = short_base; - while(i--) - code += v[i]; - v = reinterpret_cast(arg + 1); - i = short_addr_t; - while(i--) - code += v[i]; - break; - - // Binary operator where first argument is an index and - // second is a variable (same as both variables). - case DisOp: - - // Binary operators where both arguments are variables - case AddvvOp: - case DivvvOp: - case MulvvOp: - case PowvvOp: - case SubvvOp: - case ZmulvvOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 2 ); - v = reinterpret_cast(arg + 0); - i = 2 * short_addr_t; - while(i--) - code += v[i]; - break; - - // Binary operators where second arugment is a parameter. - case DivvpOp: - case PowvpOp: - case SubvpOp: - case ZmulvpOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 2 ); - v = reinterpret_cast(arg + 0); - i = short_addr_t; - while(i--) - code += v[i]; - v = reinterpret_cast(par + arg[1]); - i = short_base; - while(i--) - code += v[i]; - break; - - // Unary operators - case AbsOp: - case AcosOp: - case AcoshOp: - case AsinOp: - case AsinhOp: - case AtanOp: - case AtanhOp: - case CosOp: - case CoshOp: - case ErfOp: - case ExpOp: - case Expm1Op: - case LogOp: - case Log1pOp: - case SignOp: - case SinOp: - case SinhOp: - case SqrtOp: - case TanOp: - case TanhOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 || op == ErfOp ); - v = reinterpret_cast(arg + 0); - i = short_addr_t; - while(i--) - code += v[i]; - break; - - // should have been one of he cases above - default: - CPPAD_ASSERT_UNKNOWN(false); - } - - return code % CPPAD_HASH_TABLE_SIZE; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/hessian.hpp b/ct_core/include/ct/external/cppad/local/hessian.hpp deleted file mode 100644 index 7c51c5ad4..000000000 --- a/ct_core/include/ct/external/cppad/local/hessian.hpp +++ /dev/null @@ -1,215 +0,0 @@ -// $Id: hessian.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_HESSIAN_HPP -# define CPPAD_HESSIAN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Hessian$$ -$spell - hes - typename - Taylor - HesLuDet - const -$$ - - -$section Hessian: Easy Driver$$ -$mindex second derivative$$ - -$head Syntax$$ -$icode%hes% = %f%.Hessian(%x%, %w%) -%$$ -$icode%hes% = %f%.Hessian(%x%, %l%) -%$$ - - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -The syntax above sets $icode hes$$ to the Hessian -The syntax above sets $icode h$$ to the Hessian -$latex \[ - hes = \dpow{2}{x} \sum_{i=1}^m w_i F_i (x) -\] $$ -The routine $cref sparse_hessian$$ may be faster in the case -where the Hessian is sparse. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/Hessian Uses Forward/Hessian/Hessian Uses Forward/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -(see $cref/Vector/Hessian/Vector/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the Hessian. - -$head l$$ -If the argument $icode l$$ is present, it has prototype -$codei% - size_t %l% -%$$ -and is less than $icode m$$, the dimension of the -$cref/range/seq_property/Range/$$ space for $icode f$$. -It specifies the component of $icode F$$ -for which we are evaluating the Hessian. -To be specific, in the case where the argument $icode l$$ is present, -$latex \[ - w_i = \left\{ \begin{array}{ll} - 1 & i = l \\ - 0 & {\rm otherwise} - \end{array} \right. -\] $$ - -$head w$$ -If the argument $icode w$$ is present, it has prototype -$codei% - const %Vector% &%w% -%$$ -and size $latex m$$. -It specifies the value of $latex w_i$$ in the expression -for $icode h$$. - -$head hes$$ -The result $icode hes$$ has prototype -$codei% - %Vector% %hes% -%$$ -(see $cref/Vector/Hessian/Vector/$$ below) -and its size is $latex n * n$$. -For $latex j = 0 , \ldots , n - 1 $$ -and $latex \ell = 0 , \ldots , n - 1$$ -$latex \[ - hes [ j * n + \ell ] = \DD{ w^{\rm T} F }{ x_j }{ x_\ell } ( x ) -\] $$ - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Base$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Hessian Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to $code Hessian$$, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0, %x%)%$$ -and the other coefficients are unspecified. - -$head Example$$ -$children% - example/hessian.cpp% - example/hes_lagrangian.cpp -%$$ -The routines -$cref hessian.cpp$$ and -$cref hes_lagrangian.cpp$$ -are examples and tests of $code Hessian$$. -They return $code true$$, if they succeed and $code false$$ otherwise. - - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -template -Vector ADFun::Hessian(const Vector &x, size_t l) -{ size_t i, m = Range(); - CPPAD_ASSERT_KNOWN( - l < m, - "Hessian: index i is not less than range dimension for f" - ); - - Vector w(m); - for(i = 0; i < m; i++) - w[i] = Base(0); - w[l] = Base(1); - - return Hessian(x, w); -} - - -template -template -Vector ADFun::Hessian(const Vector &x, const Vector &w) -{ size_t j; - size_t k; - - size_t n = Domain(); - - // check Vector is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( - size_t(x.size()) == n, - "Hessian: length of x not equal domain dimension for f" - ); - CPPAD_ASSERT_KNOWN( - size_t(w.size()) == Range(), - "Hessian: length of w not equal range dimension for f" - ); - - // point at which we are evaluating the Hessian - Forward(0, x); - - // define the return value - Vector hes(n * n); - - // direction vector for calls to forward - Vector u(n); - for(j = 0; j < n; j++) - u[j] = Base(0); - - - // location for return values from Reverse - Vector ddw(n * 2); - - // loop over forward directions - for(j = 0; j < n; j++) - { // evaluate partials of entire function w.r.t. j-th coordinate - u[j] = Base(1); - Forward(1, u); - u[j] = Base(0); - - // evaluate derivative of partial corresponding to F_i - ddw = Reverse(2, w); - - // return desired components - for(k = 0; k < n; k++) - hes[k * n + j] = ddw[k * 2 + 1]; - } - - return hes; -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/identical.hpp b/ct_core/include/ct/external/cppad/local/identical.hpp deleted file mode 100644 index a7dddd159..000000000 --- a/ct_core/include/ct/external/cppad/local/identical.hpp +++ /dev/null @@ -1,105 +0,0 @@ -// $Id: identical.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_IDENTICAL_HPP -# define CPPAD_IDENTICAL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file identical.hpp -Check if certain properties is true for any possible AD tape play back. -*/ - -// --------------------------------------------------------------------------- -/*! -Determine if an AD object is a parameter, and could never have -a different value during any tape playback. - -An AD object \c x is identically a parameter if and only if -all of the objects in the following chain are parameters: -\code - x , x.value , x.value.value , ... -\endcode -In such a case, the value of the object will always be the same -no matter what the independent variable values are at any level. - -\param x -values that we are checking for identically a pamameter. - -\return -returns true iff \c x is identically a parameter. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool IdenticalPar(const AD &x) -{ return Parameter(x) && IdenticalPar(x.value_); } -// Zero ============================================================== -/*! -Determine if an AD is equal to zero, -and must be equal zero during any tape playback. - -\param x -object that we are checking. - -\return -returns true if and only if -\c x is equals zero and is identically a parameter \ref IdenticalPar. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool IdenticalZero(const AD &x) -{ return Parameter(x) && IdenticalZero(x.value_); } -// One ============================================================== -/*! -Determine if an AD is equal to one, -and must be equal one during any tape playback. - -\param x -object that we are checking. - -\return -returns true if and only if -\c x is equals one and is identically a parameter \ref IdenticalPar. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool IdenticalOne(const AD &x) -{ return Parameter(x) && IdenticalOne(x.value_); } -// Equal =================================================================== -/*! -Determine if two AD objects are equal, -and must be equal during any tape playback. - -\param x -first of two objects we are checking for equal. - -\param y -second of two objects we are checking for equal. - -\return -returns true if and only if -the arguments are equal and both identically parameters \ref IdenticalPar. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool IdenticalEqualPar -(const AD &x, const AD &y) -{ bool parameter; - parameter = ( Parameter(x) & Parameter(y) ); - return parameter && IdenticalEqualPar(x.value_, y.value_); -} -// ========================================================================== - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/independent.hpp b/ct_core/include/ct/external/cppad/local/independent.hpp deleted file mode 100644 index f209c8449..000000000 --- a/ct_core/include/ct/external/cppad/local/independent.hpp +++ /dev/null @@ -1,189 +0,0 @@ -// $Id: independent.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_INDEPENDENT_HPP -# define CPPAD_INDEPENDENT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* ---------------------------------------------------------------------------- - -$begin Independent$$ -$spell - op - alloc - num - Cpp - bool - const - var - typename -$$ - -$section Declare Independent Variables and Start Recording$$ - -$head Syntax$$ -$codei%Independent(%x%) -%$$ -$codei%Independent(%x%, %abort_op_index%) -%$$ - -$head Purpose$$ -Start recording -$cref/AD of Base/glossary/AD of Base/$$ operations -with $icode x$$ as the independent variable vector. -Once the -$cref/operation sequence/glossary/Operation/Sequence/$$ is completed, -it must be transferred to a function object; see below. - -$head Start Recording$$ -An operation sequence recording is started by the commands -$codei% - Independent(%x%) - Independent(%x%, %abort_op_index%) -%$$ - -$head Stop Recording$$ -The recording is stopped, -and the operation sequence is transferred to the AD function object $icode f$$, -using either the $cref/function constructor/FunConstruct/$$ -$codei% - ADFun<%Base%> %f%(%x%, %y%) -%$$ -or the $cref/dependent variable specifier/Dependent/$$ -$codei% - %f%.Dependent(%x%, %y%) -%$$ -The only other way to stop a recording is using -$cref abort_recording$$. -Between when the recording is started and when it stopped, -we refer to the elements of $icode x$$, -and the values that depend on the elements of $icode x$$, -as $codei%AD<%Base%>%$$ variables. - -$head x$$ -The vector $icode x$$ has prototype -$codei% - %VectorAD% &%x% -%$$ -(see $icode VectorAD$$ below). -The size of the vector $icode x$$, must be greater than zero, -and is the number of independent variables for this -AD operation sequence. - -$head abort_op_index$$ -It specifies the operator index at which the execution is be aborted -by calling the CppAD $cref/error handler/ErrorHandler/$$. -When this error handler leads to an assert, the user -can inspect the call stack to see the source code corresponding to -this operator index; see -$cref/purpose/compare_change/op_index/Purpose/$$. -No abort will occur if $icode abort_op_index$$ is zero, -of if $cref/NDEBUG/Faq/Speed/NDEBUG/$$ is defined. - -$head VectorAD$$ -The type $icode VectorAD$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$codei%AD<%Base%>%$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Parallel Mode$$ -Each thread can have one, and only one, active recording. -A call to $code Independent$$ starts the recording for the current thread. -The recording must be stopped by a corresponding call to -$codei% - ADFun<%Base%> %f%( %x%, %y%) -%$$ -or -$codei% - %f%.Dependent( %x%, %y%) -%$$ -or $cref abort_recording$$ -preformed by the same thread; i.e., -$cref/thread_alloc::thread_num/ta_thread_num/$$ must be the same. - -$head Example$$ -$children% - example/independent.cpp -%$$ -The file -$cref independent.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { -// --------------------------------------------------------------------------- - -template -template -void ADTape::Independent(VectorAD &x, size_t abort_op_index) -{ - // check VectorAD is Simple Vector class with AD elements - CheckSimpleVector< AD, VectorAD>(); - - // dimension of the domain space - size_t n = x.size(); - CPPAD_ASSERT_KNOWN( - n > 0, - "Indepdendent: the argument vector x has zero size" - ); - CPPAD_ASSERT_UNKNOWN( Rec_.num_var_rec() == 0 ); - - // set the abort index before doing anything else - Rec_.set_abort_op_index(abort_op_index); - - // mark the beginning of the tape and skip the first variable index - // (zero) because parameters use taddr zero - CPPAD_ASSERT_NARG_NRES(BeginOp, 1, 1); - Rec_.PutOp(BeginOp); - Rec_.PutArg(0); - - // place each of the independent variables in the tape - CPPAD_ASSERT_NARG_NRES(InvOp, 0, 1); - size_t j; - for(j = 0; j < n; j++) - { // tape address for this independent variable - x[j].taddr_ = Rec_.PutOp(InvOp); - x[j].tape_id_ = id_; - CPPAD_ASSERT_UNKNOWN( size_t(x[j].taddr_) == j+1 ); - CPPAD_ASSERT_UNKNOWN( Variable(x[j] ) ); - } - - // done specifying all of the independent variables - size_independent_ = n; -} - -template -inline void Independent(VectorAD &x, size_t abort_op_index) -{ typedef typename VectorAD::value_type ADBase; - typedef typename ADBase::value_type Base; - CPPAD_ASSERT_KNOWN( - ADBase::tape_ptr() == CPPAD_NULL, - "Independent: cannot create a new tape because\n" - "a previous tape is still active (for this thread).\n" - "AD::abort_recording() would abort this previous recording." - ); - ADTape* tape = ADBase::tape_manage(tape_manage_new); - tape->Independent(x, abort_op_index); -} -template -inline void Independent(VectorAD &x) -{ size_t abort_op_index = 0; - Independent(x, abort_op_index); } -} -// END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/integer.hpp b/ct_core/include/ct/external/cppad/local/integer.hpp deleted file mode 100644 index 691bc946d..000000000 --- a/ct_core/include/ct/external/cppad/local/integer.hpp +++ /dev/null @@ -1,113 +0,0 @@ -// $Id: integer.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_INTEGER_HPP -# define CPPAD_INTEGER_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ------------------------------------------------------------------------------- -$begin Integer$$ -$spell - std - VecAD - CppAD - namespace - const - bool -$$ - - - -$section Convert From AD to Integer$$ - -$head Syntax$$ -$icode%i% = Integer(%x%)%$$ - - -$head Purpose$$ -Converts from an AD type to the corresponding integer value. - -$head i$$ -The result $icode i$$ has prototype -$codei% - int %i% -%$$ - -$head x$$ - -$subhead Real Types$$ -If the argument $icode x$$ has either of the following prototypes: -$codei% - const float %% &%x% - const double %% &%x% -%$$ -the fractional part is dropped to form the integer value. -For example, if $icode x$$ is 1.5, $icode i$$ is 1. -In general, if $latex x \geq 0$$, $icode i$$ is the -greatest integer less than or equal $icode x$$. -If $latex x \leq 0$$, $icode i$$ is the -smallest integer greater than or equal $icode x$$. - -$subhead Complex Types$$ -If the argument $icode x$$ has either of the following prototypes: -$codei% - const std::complex %% &%x% - const std::complex %% &%x% -%$$ -The result $icode i$$ is given by -$codei% - %i% = Integer(%x%.real()) -%$$ - -$subhead AD Types$$ -If the argument $icode x$$ has either of the following prototypes: -$codei% - const AD<%Base%> &%x% - const VecAD<%Base%>::reference &%x% -%$$ -$icode Base$$ must support the $code Integer$$ function and -the conversion has the same meaning as for $icode Base$$. - -$head Operation Sequence$$ -The result of this operation is not an -$cref/AD of Base/glossary/AD of Base/$$ object. -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Example$$ -$children% - example/integer.cpp -%$$ -The file -$cref integer.cpp$$ -contains an example and test of this operation. - -$end ------------------------------------------------------------------------------- -*/ - - -namespace CppAD { - - template - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION - int Integer(const AD &x) - { return Integer(x.value_); } - - template - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION - int Integer(const VecAD_reference &x) - { return Integer( x.ADBase() ); } -} -# endif - diff --git a/ct_core/include/ct/external/cppad/local/jacobian.hpp b/ct_core/include/ct/external/cppad/local/jacobian.hpp deleted file mode 100644 index e7fc91b1d..000000000 --- a/ct_core/include/ct/external/cppad/local/jacobian.hpp +++ /dev/null @@ -1,234 +0,0 @@ -// $Id: jacobian.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_JACOBIAN_HPP -# define CPPAD_JACOBIAN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Jacobian$$ -$spell - jac - typename - Taylor - Jacobian - DetLu - const -$$ - - -$section Jacobian: Driver Routine$$ -$mindex Jacobian first derivative$$ - -$head Syntax$$ -$icode%jac% = %f%.Jacobian(%x%)%$$ - - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -The syntax above sets $icode jac$$ to the -Jacobian of $icode F$$ evaluated at $icode x$$; i.e., -$latex \[ - jac = F^{(1)} (x) -\] $$ - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/Forward or Reverse/Jacobian/Forward or Reverse/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -(see $cref/Vector/Jacobian/Vector/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the Jacobian. - -$head jac$$ -The result $icode jac$$ has prototype -$codei% - %Vector% %jac% -%$$ -(see $cref/Vector/Jacobian/Vector/$$ below) -and its size is $latex m * n$$; i.e., the product of the -$cref/domain/seq_property/Domain/$$ -and -$cref/range/seq_property/Range/$$ -dimensions for $icode f$$. -For $latex i = 0 , \ldots , m - 1 $$ -and $latex j = 0 , \ldots , n - 1$$ -$latex \[. - jac[ i * n + j ] = \D{ F_i }{ x_j } ( x ) -\] $$ - - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Base$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Forward or Reverse$$ -This will use order zero Forward mode and either -order one Forward or order one Reverse to compute the Jacobian -(depending on which it estimates will require less work). -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to $code Jacobian$$, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0, %x%)%$$ -and the other coefficients are unspecified. - -$head Example$$ -$children% - example/jacobian.cpp -%$$ -The routine -$cref/Jacobian/jacobian.cpp/$$ is both an example and test. -It returns $code true$$, if it succeeds and $code false$$ otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -void JacobianFor(ADFun &f, const Vector &x, Vector &jac) -{ size_t i; - size_t j; - - size_t n = f.Domain(); - size_t m = f.Range(); - - // check Vector is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_UNKNOWN( size_t(x.size()) == f.Domain() ); - CPPAD_ASSERT_UNKNOWN( size_t(jac.size()) == f.Range() * f.Domain() ); - - // argument and result for forward mode calculations - Vector u(n); - Vector v(m); - - // initialize all the components - for(j = 0; j < n; j++) - u[j] = Base(0); - - // loop through the different coordinate directions - for(j = 0; j < n; j++) - { // set u to the j-th coordinate direction - u[j] = Base(1); - - // compute the partial of f w.r.t. this coordinate direction - v = f.Forward(1, u); - - // reset u to vector of all zeros - u[j] = Base(0); - - // return the result - for(i = 0; i < m; i++) - jac[ i * n + j ] = v[i]; - } -} -template -void JacobianRev(ADFun &f, const Vector &x, Vector &jac) -{ size_t i; - size_t j; - - size_t n = f.Domain(); - size_t m = f.Range(); - - CPPAD_ASSERT_UNKNOWN( size_t(x.size()) == f.Domain() ); - CPPAD_ASSERT_UNKNOWN( size_t(jac.size()) == f.Range() * f.Domain() ); - - // argument and result for reverse mode calculations - Vector u(n); - Vector v(m); - - // initialize all the components - for(i = 0; i < m; i++) - v[i] = Base(0); - - // loop through the different coordinate directions - for(i = 0; i < m; i++) - { if( f.Parameter(i) ) - { // return zero for this component of f - for(j = 0; j < n; j++) - jac[ i * n + j ] = Base(0); - } - else - { - // set v to the i-th coordinate direction - v[i] = Base(1); - - // compute the derivative of this component of f - u = f.Reverse(1, v); - - // reset v to vector of all zeros - v[i] = Base(0); - - // return the result - for(j = 0; j < n; j++) - jac[ i * n + j ] = u[j]; - } - } -} - -template -template -Vector ADFun::Jacobian(const Vector &x) -{ size_t i; - size_t n = Domain(); - size_t m = Range(); - - CPPAD_ASSERT_KNOWN( - size_t(x.size()) == n, - "Jacobian: length of x not equal domain dimension for F" - ); - - // point at which we are evaluating the Jacobian - Forward(0, x); - - // work factor for forward mode - size_t workForward = n; - - // work factor for reverse mode - size_t workReverse = 0; - for(i = 0; i < m; i++) - { if( ! Parameter(i) ) - ++workReverse; - } - - // choose the method with the least work - Vector jac( n * m ); - if( workForward <= workReverse ) - JacobianFor(*this, x, jac); - else JacobianRev(*this, x, jac); - - return jac; -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/load_op.hpp b/ct_core/include/ct/external/cppad/local/load_op.hpp deleted file mode 100644 index 775f9fc1f..000000000 --- a/ct_core/include/ct/external/cppad/local/load_op.hpp +++ /dev/null @@ -1,688 +0,0 @@ -// $Id: load_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_LOAD_OP_HPP -# define CPPAD_LOAD_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file load_op.hpp -Setting a variable so that it corresponds to current value of a VecAD element. -*/ -/* -============================================================================== - -The C++ source code corresponding to this operation is -\verbatim - v[x] = y -\endverbatim -where v is a VecAD vector, x is an AD object, -and y is AD or Base objects. -We define the index corresponding to v[x] by -\verbatim - i_v_x = index_by_ind[ arg[0] + i_vec ] -\endverbatim -where i_vec is defined under the heading arg[1] below: - -============================================================================== -*/ -/*! -Shared documentation for zero order forward mode implementation of -op = LdpOp or LdvOp (not called). - - -The C++ source code corresponding to this operation is -\verbatim - v[x] = y -\endverbatim -where v is a VecAD vector, x is an AD object, -and y is AD or Base objects. -We define the index corresponding to v[x] by -\verbatim - i_v_x = index_by_ind[ arg[0] + i_vec ] -\endverbatim -where i_vec is defined under the heading arg[1] below: - - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD and computations by this routine are done using type Base. - -\param play -is the tape that this operation appears in. -This is for error detection and not used when NDEBUG is defined. - -\param i_z -is the AD variable index corresponding to the variable z. - -\param arg -\n -arg[0] -is the offset of this VecAD vector relative to the beginning -of the isvar_by_ind and index)_by_ind arrays. -\n -\n -arg[1] -\n -If this is the LdpOp operation (if x is a parameter), -i_vec is defined by -\verbatim - i_vec = arg[1] -\endverbatim -If this is the LdvOp operation (if x is a variable), -i_vec is defined by -\verbatim - i_vec = floor( taylor[ arg[1] * cap_order + 0 ] ) -\endverbatim -where floor(c) is the greatest integer less that or equal c. -\n -\n -arg[2] -Is the index of this vecad load instruction in the -var_by_load_op array. - -\param parameter -If v[x] is a parameter, parameter[ i_v_x ] is its value. -This vector has size play->num_par_rec(). - -\param cap_order -number of columns in the matrix containing the Taylor coefficients. - -\param taylor -\n -Input -\n -In LdvOp case, taylor[ arg[1] * cap_order + 0 ] -is used to compute the index in the definition of i_vec above. -If v[x] is a variable, taylor[ i_v_x * cap_order + 0 ] -is the zero order Taylor coefficient for v[x]. -\n -\n -Output -\n -taylor[ i_z * cap_order + 0 ] -is set to the zero order Taylor coefficient for the variable z. - -\param isvar_by_ind -If isvar_by_ind[ arg[0] + i_vec ] is true, -v[x] is a variable. Otherwise it is a parameter. -This vector has size play->num_vec_ind_rec(). - -\param index_by_ind -index_by_ind[ arg[0] - 1 ] -is the number of elements in the user vector containing this element. -index_by_ind[ arg[0] + i_vec ] is the variable or -parameter index for this element, -This array has size play->num_vec_ind_rec(). - -\param var_by_load_op -is a vector with size play->num_load_op_rec(). -The input value of its elements does not matter. -Upon return, it contains the variable index corresponding to each load -instruction. -In the case where the index is zero, -the instruction corresponds to a parameter (not variable). -This array has size play->num_load_op_rec(). - -\par Check User Errors -\li In the LdvOp case check that the index is with in range; i.e. -i_vec < index_by_ind[ arg[0] - 1 ]. -Note that, if x is a parameter, -the corresponding vector index and it does not change. -In this case, the error above should be detected during tape recording. -*/ -template -inline void forward_load_op_0( - player* play , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor , - bool* isvar_by_ind , - size_t* index_by_ind , - addr_t* var_by_load_op ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} -/*! -Shared documentation for sparsity operations corresponding to -op = LdpOp or LdvOp (not called). - - -The C++ source code corresponding to this operation is -\verbatim - v[x] = y -\endverbatim -where v is a VecAD vector, x is an AD object, -and y is AD or Base objects. -We define the index corresponding to v[x] by -\verbatim - i_v_x = index_by_ind[ arg[0] + i_vec ] -\endverbatim -where i_vec is defined under the heading arg[1] below: - - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param op -is the code corresponding to this operator; -i.e., LdpOp or LdvOp. - -\param i_z -is the AD variable index corresponding to the variable z; i.e., -the set with index \a i_z in \a var_sparsity is the sparsity pattern -correpsonding to z. - -\param arg -\n -\a arg[0] -is the offset corresponding to this VecAD vector in the VecAD combined array. - -\param num_combined -is the total number of elements in the VecAD combinded array. - -\param combined -is the VecAD combined array. -\n -\n -\a combined[ \a arg[0] - 1 ] -is the index of the set corresponding to the vector v in \a vecad_sparsity. -We use the notation i_v for this value; i.e., -\verbatim - i_v = combined[ \a arg[0] - 1 ] -\endverbatim - -\param var_sparsity -The set with index \a i_z in \a var_sparsity is the sparsity pattern for z. -This is an output for forward mode operations, -and an input for reverse mode operations. - -\param vecad_sparsity -The set with index \a i_v is the sparsity pattern for the vector v. -This is an input for forward mode operations. -For reverse mode operations, -the sparsity pattern for z is added to the sparsity pattern for v. - -\par Checked Assertions -\li NumArg(op) == 3 -\li NumRes(op) == 1 -\li 0 < \a arg[0] -\li \a arg[0] < \a num_combined -\li i_v < \a vecad_sparsity.n_set() -*/ -template -inline void sparse_load_op( - OpCode op , - size_t i_z , - const addr_t* arg , - size_t num_combined , - const size_t* combined , - Vector_set& var_sparsity , - Vector_set& vecad_sparsity ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} - - -/*! -Zero order forward mode implementation of op = LdpOp. - -\copydetails forward_load_op_0 -*/ -template -inline void forward_load_p_op_0( - player* play , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor , - bool* isvar_by_ind , - size_t* index_by_ind , - addr_t* var_by_load_op ) -{ CPPAD_ASSERT_UNKNOWN( NumArg(LdpOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(LdpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < play->num_load_op_rec() ); - - // Because the index is a parameter, this indexing error should have been - // caught and reported to the user when the tape is recording. - size_t i_vec = arg[1]; - CPPAD_ASSERT_UNKNOWN( i_vec < index_by_ind[ arg[0] - 1 ] ); - CPPAD_ASSERT_UNKNOWN( arg[0] + i_vec < play->num_vec_ind_rec() ); - - size_t i_v_x = index_by_ind[ arg[0] + i_vec ]; - Base* z = taylor + i_z * cap_order; - if( isvar_by_ind[ arg[0] + i_vec ] ) - { CPPAD_ASSERT_UNKNOWN( i_v_x < i_z ); - var_by_load_op[ arg[2] ] = i_v_x; - Base* v_x = taylor + i_v_x * cap_order; - z[0] = v_x[0]; - } - else - { CPPAD_ASSERT_UNKNOWN( i_v_x < play->num_par_rec() ); - var_by_load_op[ arg[2] ] = 0; - Base v_x = parameter[i_v_x]; - z[0] = v_x; - } -} - -/*! -Zero order forward mode implementation of op = LdvOp. - -\copydetails forward_load_op_0 -*/ -template -inline void forward_load_v_op_0( - player* play , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor , - bool* isvar_by_ind , - size_t* index_by_ind , - addr_t* var_by_load_op ) -{ CPPAD_ASSERT_UNKNOWN( NumArg(LdvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(LdvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < play->num_load_op_rec() ); - - size_t i_vec = Integer( taylor[ arg[1] * cap_order + 0 ] ); - CPPAD_ASSERT_KNOWN( - i_vec < index_by_ind[ arg[0] - 1 ] , - "VecAD: index during zero order forward sweep is out of range" - ); - CPPAD_ASSERT_UNKNOWN( arg[0] + i_vec < play->num_vec_ind_rec() ); - - size_t i_v_x = index_by_ind[ arg[0] + i_vec ]; - Base* z = taylor + i_z * cap_order; - if( isvar_by_ind[ arg[0] + i_vec ] ) - { CPPAD_ASSERT_UNKNOWN( i_v_x < i_z ); - var_by_load_op[ arg[2] ] = i_v_x; - Base* v_x = taylor + i_v_x * cap_order; - z[0] = v_x[0]; - } - else - { CPPAD_ASSERT_UNKNOWN( i_v_x < play->num_par_rec() ); - var_by_load_op[ arg[2] ] = 0; - Base v_x = parameter[i_v_x]; - z[0] = v_x; - } -} - -/*! -Forward mode, except for zero order, for op = LdpOp or op = LdvOp - - - -The C++ source code corresponding to this operation is -\verbatim - v[x] = y -\endverbatim -where v is a VecAD vector, x is an AD object, -and y is AD or Base objects. -We define the index corresponding to v[x] by -\verbatim - i_v_x = index_by_ind[ arg[0] + i_vec ] -\endverbatim -where i_vec is defined under the heading arg[1] below: - - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD and computations by this routine are done using type Base. - -\param play -is the tape that this operation appears in. -This is for error detection and not used when NDEBUG is defined. - -\param op -is the code corresponding to this operator; i.e., LdpOp or LdvOp -(only used for error checking). - -\param p -is the lowest order of the Taylor coefficient that we are computing. - -\param q -is the highest order of the Taylor coefficient that we are computing. - -\param r -is the number of directions for the Taylor coefficients that we -are computing. - -\param cap_order -number of columns in the matrix containing the Taylor coefficients. - -\par tpv -We use the notation -tpv = (cap_order-1) * r + 1 -which is the number of Taylor coefficients per variable - -\param i_z -is the AD variable index corresponding to the variable z. - -\param arg -arg[2] -Is the index of this vecad load instruction in the var_by_load_op array. - -\param var_by_load_op -is a vector with size play->num_load_op_rec(). -It contains the variable index corresponding to each load instruction. -In the case where the index is zero, -the instruction corresponds to a parameter (not variable). - -\par i_var -We use the notation -\verbatim - i_var = size_t( var_by_load_op[ arg[2] ] ) -\endverbatim - -\param taylor -\n -Input -\n -If i_var > 0, v[x] is a variable and -for k = 1 , ... , q -taylor[ i_var * tpv + (k-1)*r+1+ell ] -is the k-th order coefficient for v[x] in the ell-th direction, -\n -\n -Output -\n -for k = p , ... , q, -taylor[ i_z * tpv + (k-1)*r+1+ell ] -is set to the k-order Taylor coefficient for z in the ell-th direction. -*/ -template -inline void forward_load_op( - const player* play , - OpCode op , - size_t p , - size_t q , - size_t r , - size_t cap_order , - size_t i_z , - const addr_t* arg , - const addr_t* var_by_load_op , - Base* taylor ) -{ - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( 0 < r); - CPPAD_ASSERT_UNKNOWN( 0 < p); - CPPAD_ASSERT_UNKNOWN( p <= q ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < play->num_load_op_rec() ); - - size_t i_var = size_t( var_by_load_op[ arg[2] ] ); - CPPAD_ASSERT_UNKNOWN( i_var < i_z ); - - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* z = taylor + i_z * num_taylor_per_var; - if( i_var > 0 ) - { Base* v_x = taylor + i_var * num_taylor_per_var; - for(size_t ell = 0; ell < r; ell++) - { for(size_t k = p; k <= q; k++) - { size_t m = (k-1) * r + 1 + ell; - z[m] = v_x[m]; - } - } - } - else - { for(size_t ell = 0; ell < r; ell++) - { for(size_t k = p; k <= q; k++) - { size_t m = (k-1) * r + 1 + ell; - z[m] = Base(0); - } - } - } -} - -/*! -Reverse mode for op = LdpOp or LdvOp. - - -The C++ source code corresponding to this operation is -\verbatim - v[x] = y -\endverbatim -where v is a VecAD vector, x is an AD object, -and y is AD or Base objects. -We define the index corresponding to v[x] by -\verbatim - i_v_x = index_by_ind[ arg[0] + i_vec ] -\endverbatim -where i_vec is defined under the heading arg[1] below: - - -This routine is given the partial derivatives of a function -G(z , y[x] , w , u ... ) -and it uses them to compute the partial derivatives of -\verbatim - H( y[x] , w , u , ... ) = G[ z( y[x] ) , y[x] , w , u , ... ] -\endverbatim - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param op -is the code corresponding to this operator; i.e., LdpOp or LdvOp -(only used for error checking). - -\param d -highest order the Taylor coefficient that we are computing the partial -derivative with respect to. - -\param i_z -is the AD variable index corresponding to the variable z. - -\param arg -\a arg[2] -Is the index of this vecad load instruction in the -var_by_load_op array. - -\param cap_order -number of columns in the matrix containing the Taylor coefficients -(not used). - -\param taylor -matrix of Taylor coefficients (not used). - -\param nc_partial -number of colums in the matrix containing all the partial derivatives -(not used if \a arg[2] is zero). - -\param partial -If \a arg[2] is zero, y[x] is a parameter -and no values need to be modified; i.e., \a partial is not used. -Otherwise, y[x] is a variable and: -\n -\n -\a partial [ \a i_z * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of G -with respect to the k-th order Taylor coefficient for z. -\n -\n -If \a arg[2] is not zero, -\a partial [ \a arg[2] * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative with respect to -the k-th order Taylor coefficient for x. -On input, it corresponds to the function G, -and on output it corresponds to the the function H. - -\param var_by_load_op -is a vector with size play->num_load_op_rec(). -It contains the variable index corresponding to each load instruction. -In the case where the index is zero, -the instruction corresponds to a parameter (not variable). - -\par Checked Assertions -\li NumArg(op) == 3 -\li NumRes(op) == 1 -\li d < cap_order -\li size_t(arg[2]) < i_z -*/ -template -inline void reverse_load_op( - OpCode op , - size_t d , - size_t i_z , - const addr_t* arg , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial , - const addr_t* var_by_load_op ) -{ size_t i_load = size_t( var_by_load_op[ arg[2] ] ); - - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( i_load < i_z ); - - if( i_load > 0 ) - { - Base* pz = partial + i_z * nc_partial; - Base* py_x = partial + i_load * nc_partial; - size_t j = d + 1; - while(j--) - py_x[j] += pz[j]; - } -} - - -/*! -Forward mode sparsity operations for LdpOp and LdvOp - -\param dependency -is this a dependency (or sparsity) calculation. - -\copydetails sparse_load_op -*/ -template -inline void forward_sparse_load_op( - bool dependency , - OpCode op , - size_t i_z , - const addr_t* arg , - size_t num_combined , - const size_t* combined , - Vector_set& var_sparsity , - Vector_set& vecad_sparsity ) -{ - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_combined ); - size_t i_v = combined[ arg[0] - 1 ]; - CPPAD_ASSERT_UNKNOWN( i_v < vecad_sparsity.n_set() ); - - var_sparsity.assignment(i_z, i_v, vecad_sparsity); - if( dependency & (op == LdvOp) ) - var_sparsity.binary_union(i_z, i_z, arg[1], var_sparsity); - - return; -} - - -/*! -Reverse mode Jacobian sparsity operations for LdpOp and LdvOp - -\param dependency -is this a dependency (or sparsity) calculation. - -\copydetails sparse_load_op -*/ -template -inline void reverse_sparse_jacobian_load_op( - bool dependency , - OpCode op , - size_t i_z , - const addr_t* arg , - size_t num_combined , - const size_t* combined , - Vector_set& var_sparsity , - Vector_set& vecad_sparsity ) -{ - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_combined ); - size_t i_v = combined[ arg[0] - 1 ]; - CPPAD_ASSERT_UNKNOWN( i_v < vecad_sparsity.n_set() ); - - vecad_sparsity.binary_union(i_v, i_v, i_z, var_sparsity); - if( dependency & (op == LdvOp) ) - var_sparsity.binary_union(arg[1], arg[1], i_z, var_sparsity); - - return; -} - - -/*! -Reverse mode Hessian sparsity operations for LdpOp and LdvOp - -\copydetails sparse_load_op - -\param var_jacobian -\a var_jacobian[i_z] -is false (true) if the Jacobian of G with respect to z is always zero -(many be non-zero). - -\param vecad_jacobian -\a vecad_jacobian[i_v] -is false (true) if the Jacobian with respect to x is always zero -(may be non-zero). -On input, it corresponds to the function G, -and on output it corresponds to the function H. - -*/ -template -inline void reverse_sparse_hessian_load_op( - OpCode op , - size_t i_z , - const addr_t* arg , - size_t num_combined , - const size_t* combined , - Vector_set& var_sparsity , - Vector_set& vecad_sparsity , - bool* var_jacobian , - bool* vecad_jacobian ) -{ - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_combined ); - size_t i_v = combined[ arg[0] - 1 ]; - CPPAD_ASSERT_UNKNOWN( i_v < vecad_sparsity.n_set() ); - - vecad_sparsity.binary_union(i_v, i_v, i_z, var_sparsity); - - vecad_jacobian[i_v] |= var_jacobian[i_z]; - - return; -} - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/log1p.hpp b/ct_core/include/ct/external/cppad/local/log1p.hpp deleted file mode 100644 index 806b44d9f..000000000 --- a/ct_core/include/ct/external/cppad/local/log1p.hpp +++ /dev/null @@ -1,92 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOG1P_HPP -# define CPPAD_LOG1P_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin log1p$$ -$spell - CppAD -$$ - -$section The Logarithm of One Plus Argument: log1p$$ - -$head Syntax$$ -$icode%y% = log1p(%x%)%$$ - -$head Description$$ -Returns the value of the logarithm of one plus argument which is defined -by $icode%y% == log(1 + %x%)%$$. - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head CPPAD_USE_CPLUSPLUS_2011$$ - -$subhead true$$ -If this preprocessor symbol is true ($code 1$$), -and $icode x$$ is an AD type, -this is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$subhead false$$ -If this preprocessor symbol is false ($code 0$$), -CppAD uses the representation -$latex \[ -\R{log1p} (x) = \log(1 + x) -\] $$ -to compute this function. - -$head Example$$ -$children% - example/log1p.cpp -%$$ -The file -$cref log1p.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ -# include -# if ! CPPAD_USE_CPLUSPLUS_2011 - -// BEGIN CppAD namespace -namespace CppAD { - -template -Type log1p_template(const Type &x) -{ return CppAD::log(Type(1) + x); -} - -inline float log1p(const float &x) -{ return log1p_template(x); } - -inline double log1p(const double &x) -{ return log1p_template(x); } - -template -inline AD log1p(const AD &x) -{ return log1p_template(x); } - -template -inline AD log1p(const VecAD_reference &x) -{ return log1p_template( x.ADBase() ); } - - -} // END CppAD namespace - -# endif // CPPAD_USE_CPLUSPLUS_2011 -# endif // CPPAD_LOG1P_INCLUDED diff --git a/ct_core/include/ct/external/cppad/local/log1p_op.hpp b/ct_core/include/ct/external/cppad/local/log1p_op.hpp deleted file mode 100644 index d94016fd1..000000000 --- a/ct_core/include/ct/external/cppad/local/log1p_op.hpp +++ /dev/null @@ -1,205 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOG1P_OP_HPP -# define CPPAD_LOG1P_OP_HPP -# if CPPAD_USE_CPLUSPLUS_2011 - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file log1p_op.hpp -Forward and reverse mode calculations for z = log1p(x). -*/ - -/*! -Compute forward mode Taylor coefficient for result of op = Log1pOp. - -The C++ source code corresponding to this operation is -\verbatim - z = log1p(x) -\endverbatim - -\copydetails forward_unary1_op -*/ -template -inline void forward_log1p_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - size_t k; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(Log1pOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(Log1pOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - - if( p == 0 ) - { z[0] = log1p( x[0] ); - p++; - if( q == 0 ) - return; - } - if ( p == 1 ) - { z[1] = x[1] / (Base(1) + x[0]); - p++; - } - for(size_t j = p; j <= q; j++) - { - z[j] = -z[1] * x[j-1]; - for(k = 2; k < j; k++) - z[j] -= Base(k) * z[k] * x[j-k]; - z[j] /= Base(j); - z[j] += x[j]; - z[j] /= (Base(1) + x[0]); - } -} - -/*! -Muiltiple directions Taylor coefficient for op = Log1pOp. - -The C++ source code corresponding to this operation is -\verbatim - z = log1p(x) -\endverbatim - -\copydetails forward_unary1_op_dir -*/ -template -inline void forward_log1p_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(Log1pOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(Log1pOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - { z[m+ell] = Base(q) * x[m+ell]; - for(size_t k = 1; k < q; k++) - z[m+ell] -= Base(k) * z[(k-1)*r+1+ell] * x[(q-k-1)*r+1+ell]; - z[m+ell] /= (Base(q) + Base(q) * x[0]); - } -} - -/*! -Compute zero order forward mode Taylor coefficient for result of op = Log1pOp. - -The C++ source code corresponding to this operation is -\verbatim - z = log1p(x) -\endverbatim - -\copydetails forward_unary1_op_0 -*/ -template -inline void forward_log1p_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(Log1pOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(Log1pOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = log1p( x[0] ); -} - -/*! -Compute reverse mode partial derivatives for result of op = Log1pOp. - -The C++ source code corresponding to this operation is -\verbatim - z = log1p(x) -\endverbatim - -\copydetails reverse_unary1_op -*/ - -template -inline void reverse_log1p_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ size_t j, k; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(Log1pOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(Log1pOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to result - const Base* z = taylor + i_z * cap_order; - Base* pz = partial + i_z * nc_partial; - - Base inv_1px0 = Base(1) / (Base(1) + x[0]); - - j = d; - while(j) - { // scale partial w.r.t z[j] - pz[j] = azmul(pz[j] , inv_1px0); - - px[0] -= azmul(pz[j], z[j]); - px[j] += pz[j]; - - // further scale partial w.r.t. z[j] - pz[j] /= Base(j); - - for(k = 1; k < j; k++) - { pz[k] -= Base(k) * azmul(pz[j], x[j-k]); - px[j-k] -= Base(k) * azmul(pz[j], z[k]); - } - --j; - } - px[0] += azmul(pz[0], inv_1px0); -} - -} // END_CPPAD_NAMESPACE -# endif -# endif diff --git a/ct_core/include/ct/external/cppad/local/log_op.hpp b/ct_core/include/ct/external/cppad/local/log_op.hpp deleted file mode 100644 index 6c39ebd87..000000000 --- a/ct_core/include/ct/external/cppad/local/log_op.hpp +++ /dev/null @@ -1,203 +0,0 @@ -// $Id: log_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_LOG_OP_HPP -# define CPPAD_LOG_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file log_op.hpp -Forward and reverse mode calculations for z = log(x). -*/ - -/*! -Compute forward mode Taylor coefficient for result of op = LogOp. - -The C++ source code corresponding to this operation is -\verbatim - z = log(x) -\endverbatim - -\copydetails forward_unary1_op -*/ -template -inline void forward_log_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - size_t k; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(LogOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(LogOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - - if( p == 0 ) - { z[0] = log( x[0] ); - p++; - if( q == 0 ) - return; - } - if ( p == 1 ) - { z[1] = x[1] / x[0]; - p++; - } - for(size_t j = p; j <= q; j++) - { - z[j] = -z[1] * x[j-1]; - for(k = 2; k < j; k++) - z[j] -= Base(k) * z[k] * x[j-k]; - z[j] /= Base(j); - z[j] += x[j]; - z[j] /= x[0]; - } -} - -/*! -Muiltiple directions Taylor coefficient for op = LogOp. - -The C++ source code corresponding to this operation is -\verbatim - z = log(x) -\endverbatim - -\copydetails forward_unary1_op_dir -*/ -template -inline void forward_log_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(LogOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(LogOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - { z[m+ell] = Base(q) * x[m+ell]; - for(size_t k = 1; k < q; k++) - z[m+ell] -= Base(k) * z[(k-1)*r+1+ell] * x[(q-k-1)*r+1+ell]; - z[m+ell] /= (Base(q) * x[0]); - } -} - -/*! -Compute zero order forward mode Taylor coefficient for result of op = LogOp. - -The C++ source code corresponding to this operation is -\verbatim - z = log(x) -\endverbatim - -\copydetails forward_unary1_op_0 -*/ -template -inline void forward_log_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(LogOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(LogOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = log( x[0] ); -} - -/*! -Compute reverse mode partial derivatives for result of op = LogOp. - -The C++ source code corresponding to this operation is -\verbatim - z = log(x) -\endverbatim - -\copydetails reverse_unary1_op -*/ - -template -inline void reverse_log_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ size_t j, k; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(LogOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(LogOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to result - const Base* z = taylor + i_z * cap_order; - Base* pz = partial + i_z * nc_partial; - - Base inv_x0 = Base(1) / x[0]; - - j = d; - while(j) - { // scale partial w.r.t z[j] - pz[j] = azmul(pz[j] , inv_x0); - - px[0] -= azmul(pz[j], z[j]); - px[j] += pz[j]; - - // further scale partial w.r.t. z[j] - pz[j] /= Base(j); - - for(k = 1; k < j; k++) - { pz[k] -= Base(k) * azmul(pz[j], x[j-k]); - px[j-k] -= Base(k) * azmul(pz[j], z[k]); - } - --j; - } - px[0] += azmul(pz[0], inv_x0); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/lu_ratio.hpp b/ct_core/include/ct/external/cppad/local/lu_ratio.hpp deleted file mode 100644 index b4ab57c5e..000000000 --- a/ct_core/include/ct/external/cppad/local/lu_ratio.hpp +++ /dev/null @@ -1,338 +0,0 @@ -// $Id: lu_ratio.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_LU_RATIO_HPP -# define CPPAD_LU_RATIO_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin LuRatio$$ -$spell - cppad.hpp - xk - Cpp - Lu - bool - const - ip - jp - std - ADvector -$$ - - -$section LU Factorization of A Square Matrix and Stability Calculation$$ -$mindex LuRatio linear equation solve$$ - -$head Syntax$$ -$code# include $$ -$pre -$$ -$icode%sign% = LuRatio(%ip%, %jp%, %LU%, %ratio%)%$$ - - -$head Description$$ -Computes an LU factorization of the matrix $icode A$$ -where $icode A$$ is a square matrix. -A measure of the numerical stability called $icode ratio$$ is calculated. -This ratio is useful when the results of $code LuRatio$$ are -used as part of an $cref ADFun$$ object. - -$head Include$$ -This routine is designed to be used with AD objects and -requires the $code cppad/cppad.hpp$$ file to be included. - -$head Matrix Storage$$ -All matrices are stored in row major order. -To be specific, if $latex Y$$ is a vector -that contains a $latex p$$ by $latex q$$ matrix, -the size of $latex Y$$ must be equal to $latex p * q $$ and for -$latex i = 0 , \ldots , p-1$$, -$latex j = 0 , \ldots , q-1$$, -$latex \[ - Y_{i,j} = Y[ i * q + j ] -\] $$ - -$head sign$$ -The return value $icode sign$$ has prototype -$codei% - int %sign% -%$$ -If $icode A$$ is invertible, $icode sign$$ is plus or minus one -and is the sign of the permutation corresponding to the row ordering -$icode ip$$ and column ordering $icode jp$$. -If $icode A$$ is not invertible, $icode sign$$ is zero. - -$head ip$$ -The argument $icode ip$$ has prototype -$codei% - %SizeVector% &%ip% -%$$ -(see description of $cref/SizeVector/LuFactor/SizeVector/$$ below). -The size of $icode ip$$ is referred to as $icode n$$ in the -specifications below. -The input value of the elements of $icode ip$$ does not matter. -The output value of the elements of $icode ip$$ determine -the order of the rows in the permuted matrix. - -$head jp$$ -The argument $icode jp$$ has prototype -$codei% - %SizeVector% &%jp% -%$$ -(see description of $cref/SizeVector/LuFactor/SizeVector/$$ below). -The size of $icode jp$$ must be equal to $icode n$$. -The input value of the elements of $icode jp$$ does not matter. -The output value of the elements of $icode jp$$ determine -the order of the columns in the permuted matrix. - -$head LU$$ -The argument $icode LU$$ has the prototype -$codei% - %ADvector% &%LU% -%$$ -and the size of $icode LU$$ must equal $latex n * n$$ -(see description of $cref/ADvector/LuRatio/ADvector/$$ below). - -$subhead A$$ -We define $icode A$$ as the matrix corresponding to the input -value of $icode LU$$. - -$subhead P$$ -We define the permuted matrix $icode P$$ in terms of $icode A$$ by -$codei% - %P%(%i%, %j%) = %A%[ %ip%[%i%] * %n% + %jp%[%j%] ] -%$$ - -$subhead L$$ -We define the lower triangular matrix $icode L$$ in terms of the -output value of $icode LU$$. -The matrix $icode L$$ is zero above the diagonal -and the rest of the elements are defined by -$codei% - %L%(%i%, %j%) = %LU%[ %ip%[%i%] * %n% + %jp%[%j%] ] -%$$ -for $latex i = 0 , \ldots , n-1$$ and $latex j = 0 , \ldots , i$$. - -$subhead U$$ -We define the upper triangular matrix $icode U$$ in terms of the -output value of $icode LU$$. -The matrix $icode U$$ is zero below the diagonal, -one on the diagonal, -and the rest of the elements are defined by -$codei% - %U%(%i%, %j%) = %LU%[ %ip%[%i%] * %n% + %jp%[%j%] ] -%$$ -for $latex i = 0 , \ldots , n-2$$ and $latex j = i+1 , \ldots , n-1$$. - -$subhead Factor$$ -If the return value $icode sign$$ is non-zero, -$codei% - %L% * %U% = %P% -%$$ -If the return value of $icode sign$$ is zero, -the contents of $icode L$$ and $icode U$$ are not defined. - -$subhead Determinant$$ -If the return value $icode sign$$ is zero, -the determinant of $icode A$$ is zero. -If $icode sign$$ is non-zero, -using the output value of $icode LU$$ -the determinant of the matrix $icode A$$ is equal to -$codei% -%sign% * %LU%[%ip%[0], %jp%[0]] * %...% * %LU%[%ip%[%n%-1], %jp%[%n%-1]] -%$$ - -$head ratio$$ -The argument $icode ratio$$ has prototype -$codei% - AD<%Base%> &%ratio% -%$$ -On input, the value of $icode ratio$$ does not matter. -On output it is a measure of how good the choice of pivots is. -For $latex p = 0 , \ldots , n-1$$, -the $th p$$ pivot element is the element of maximum absolute value of a -$latex (n-p) \times (n-p)$$ sub-matrix. -The ratio of each element of sub-matrix divided by the pivot element -is computed. -The return value of $icode ratio$$ is the maximum absolute value of -such ratios over with respect to all elements and all the pivots. - -$subhead Purpose$$ -Suppose that the execution of a call to $code LuRatio$$ -is recorded in the $codei%ADFun<%Base%>%$$ object $icode F$$. -Then a call to $cref Forward$$ of the form -$codei% - %F%.Forward(%k%, %xk%) -%$$ -with $icode k$$ equal to zero will revaluate this Lu factorization -with the same pivots and a new value for $icode A$$. -In this case, the resulting $icode ratio$$ may not be one. -If $icode ratio$$ is too large (the meaning of too large is up to you), -the current pivots do not yield a stable LU factorization of $icode A$$. -A better choice for the pivots (for this value of $icode A$$) -will be made if you recreate the $code ADFun$$ object -starting with the $cref Independent$$ variable values -that correspond to the vector $icode xk$$. - -$head SizeVector$$ -The type $icode SizeVector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type size_t/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head ADvector$$ -The type $icode ADvector$$ must be a -$cref/simple vector class/SimpleVector/$$ with elements of type -$codei%AD<%Base%>%$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - - -$head Example$$ -$children% - example/lu_ratio.cpp -%$$ -The file $cref lu_ratio.cpp$$ -contains an example and test of using $code LuRatio$$. -It returns true if it succeeds and false otherwise. - -$end --------------------------------------------------------------------------- -*/ -namespace CppAD { // BEGIN CppAD namespace - -// Lines different from the code in cppad/lu_factor.hpp end with // -template // -int LuRatio(SizeVector &ip, SizeVector &jp, ADvector &LU, AD &ratio) // -{ - typedef ADvector FloatVector; // - typedef AD Float; // - - // check numeric type specifications - CheckNumericType(); - - // check simple vector class specifications - CheckSimpleVector(); - CheckSimpleVector(); - - size_t i, j; // some temporary indices - const Float zero( 0 ); // the value zero as a Float object - size_t imax; // row index of maximum element - size_t jmax; // column indx of maximum element - Float emax; // maximum absolute value - size_t p; // count pivots - int sign; // sign of the permutation - Float etmp; // temporary element - Float pivot; // pivot element - - // ------------------------------------------------------- - size_t n = size_t(ip.size()); - CPPAD_ASSERT_KNOWN( - size_t(jp.size()) == n, - "Error in LuFactor: jp must have size equal to n" - ); - CPPAD_ASSERT_KNOWN( - size_t(LU.size()) == n * n, - "Error in LuFactor: LU must have size equal to n * m" - ); - // ------------------------------------------------------- - - // initialize row and column order in matrix not yet pivoted - for(i = 0; i < n; i++) - { ip[i] = i; - jp[i] = i; - } - // initialize the sign of the permutation - sign = 1; - // initialize the ratio // - ratio = Float(1); // - // --------------------------------------------------------- - - // Reduce the matrix P to L * U using n pivots - for(p = 0; p < n; p++) - { // determine row and column corresponding to element of - // maximum absolute value in remaining part of P - imax = jmax = n; - emax = zero; - for(i = p; i < n; i++) - { for(j = p; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( - (ip[i] < n) & (jp[j] < n) - ); - etmp = LU[ ip[i] * n + jp[j] ]; - - // check if maximum absolute value so far - if( AbsGeq (etmp, emax) ) - { imax = i; - jmax = j; - emax = etmp; - } - } - } - for(i = p; i < n; i++) // - { for(j = p; j < n; j++) // - { etmp = abs(LU[ ip[i] * n + jp[j] ] / emax); // - ratio = // - CondExpGt(etmp, ratio, etmp, ratio); // - } // - } // - CPPAD_ASSERT_KNOWN( - (imax < n) & (jmax < n) , - "AbsGeq must return true when second argument is zero" - ); - if( imax != p ) - { // switch rows so max absolute element is in row p - i = ip[p]; - ip[p] = ip[imax]; - ip[imax] = i; - sign = -sign; - } - if( jmax != p ) - { // switch columns so max absolute element is in column p - j = jp[p]; - jp[p] = jp[jmax]; - jp[jmax] = j; - sign = -sign; - } - // pivot using the max absolute element - pivot = LU[ ip[p] * n + jp[p] ]; - - // check for determinant equal to zero - if( pivot == zero ) - { // abort the mission - return 0; - } - - // Reduce U by the elementary transformations that maps - // LU( ip[p], jp[p] ) to one. Only need transform elements - // above the diagonal in U and LU( ip[p] , jp[p] ) is - // corresponding value below diagonal in L. - for(j = p+1; j < n; j++) - LU[ ip[p] * n + jp[j] ] /= pivot; - - // Reduce U by the elementary transformations that maps - // LU( ip[i], jp[p] ) to zero. Only need transform elements - // above the diagonal in U and LU( ip[i], jp[p] ) is - // corresponding value below diagonal in L. - for(i = p+1; i < n; i++ ) - { etmp = LU[ ip[i] * n + jp[p] ]; - for(j = p+1; j < n; j++) - { LU[ ip[i] * n + jp[j] ] -= - etmp * LU[ ip[p] * n + jp[j] ]; - } - } - } - return sign; -} -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/mul.hpp b/ct_core/include/ct/external/cppad/local/mul.hpp deleted file mode 100644 index a05b70537..000000000 --- a/ct_core/include/ct/external/cppad/local/mul.hpp +++ /dev/null @@ -1,102 +0,0 @@ -// $Id: mul.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_MUL_HPP -# define CPPAD_MUL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD operator * (const AD &left , const AD &right) -{ - // compute the Base part - AD result; - result.value_ = left.value_ * right.value_; - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - // check if there is a recording in progress - ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return result; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = left.tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // result = variable * variable - CPPAD_ASSERT_UNKNOWN( NumRes(MulvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(MulvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(left.taddr_, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(MulvvOp); - // make result a variable - result.tape_id_ = tape_id; - } - else if( IdenticalZero(right.value_) ) - { // result = variable * 0 - } - else if( IdenticalOne(right.value_) ) - { // result = variable * 1 - result.make_variable(left.tape_id_, left.taddr_); - } - else - { // result = variable * parameter - CPPAD_ASSERT_UNKNOWN( NumRes(MulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(MulpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(p, left.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(MulpvOp); - // make result a variable - result.tape_id_ = tape_id; - } - } - else if( var_right ) - { if( IdenticalZero(left.value_) ) - { // result = 0 * variable - } - else if( IdenticalOne(left.value_) ) - { // result = 1 * variable - result.make_variable(right.tape_id_, right.taddr_); - } - else - { // result = parameter * variable - CPPAD_ASSERT_UNKNOWN( NumRes(MulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(MulpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left.value_); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(MulpvOp); - // make result a variable - result.tape_id_ = tape_id; - } - } - return result; -} - -// convert other cases into the case above -CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR(*) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/mul_eq.hpp b/ct_core/include/ct/external/cppad/local/mul_eq.hpp deleted file mode 100644 index 3057266cf..000000000 --- a/ct_core/include/ct/external/cppad/local/mul_eq.hpp +++ /dev/null @@ -1,102 +0,0 @@ -// $Id: mul_eq.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_MUL_EQ_HPP -# define CPPAD_MUL_EQ_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD& AD::operator *= (const AD &right) -{ - // compute the Base part - Base left; - left = value_; - value_ *= right.value_; - - // check if there is a recording in progress - ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return *this; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // this = variable * variable - CPPAD_ASSERT_UNKNOWN( NumRes(MulvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(MulvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(taddr_, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(MulvvOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - else if( IdenticalOne( right.value_ ) ) - { // this = variable * 1 - } - else if( IdenticalZero( right.value_ ) ) - { // this = variable * 0 - make_parameter(); - } - else - { // this = variable * parameter - // = parameter * variable - CPPAD_ASSERT_UNKNOWN( NumRes(MulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(MulpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(p, taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(MulpvOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - } - else if( var_right ) - { if( IdenticalZero(left) ) - { // this = 0 * right - } - else if( IdenticalOne(left) ) - { // this = 1 * right - make_variable(right.tape_id_, right.taddr_); - } - else - { // this = parameter * variable - CPPAD_ASSERT_UNKNOWN( NumRes(MulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(MulpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(MulpvOp); - // make this a variable - tape_id_ = tape_id; - } - } - return *this; -} - -CPPAD_FOLD_ASSIGNMENT_OPERATOR(*=) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/mul_op.hpp b/ct_core/include/ct/external/cppad/local/mul_op.hpp deleted file mode 100644 index 9bf291a3e..000000000 --- a/ct_core/include/ct/external/cppad/local/mul_op.hpp +++ /dev/null @@ -1,360 +0,0 @@ -// $Id: mul_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_MUL_OP_HPP -# define CPPAD_MUL_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file mul_op.hpp -Forward and reverse mode calculations for z = x * y. -*/ - -// --------------------------- Mulvv ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = MulvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x * y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_binary_op -*/ - -template -inline void forward_mulvv_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(MulvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(MulvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - size_t k; - for(size_t d = p; d <= q; d++) - { z[d] = Base(0); - for(k = 0; k <= d; k++) - z[d] += x[d-k] * y[k]; - } -} -/*! -Multiple directions forward mode Taylor coefficients for op = MulvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x * y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_binary_op_dir -*/ - -template -inline void forward_mulvv_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(MulvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(MulvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to arguments and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + arg[0] * num_taylor_per_var; - Base* y = taylor + arg[1] * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - - size_t k, ell, m; - for(ell = 0; ell < r; ell++) - { m = (q-1)*r + ell + 1; - z[m] = x[0] * y[m] + x[m] * y[0]; - for(k = 1; k < q; k++) - z[m] += x[(q-k-1)*r + ell + 1] * y[(k-1)*r + ell + 1]; - } -} - -/*! -Compute zero order forward mode Taylor coefficients for result of op = MulvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x * y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_binary_op_0 -*/ - -template -inline void forward_mulvv_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(MulvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(MulvvOp) == 1 ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = x[0] * y[0]; -} - -/*! -Compute reverse mode partial derivatives for result of op = MulvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x * y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails reverse_binary_op -*/ - -template -inline void reverse_mulvv_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(MulvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(MulvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Arguments - const Base* x = taylor + arg[0] * cap_order; - const Base* y = taylor + arg[1] * cap_order; - - // Partial derivatives corresponding to arguments and result - Base* px = partial + arg[0] * nc_partial; - Base* py = partial + arg[1] * nc_partial; - Base* pz = partial + i_z * nc_partial; - - - // number of indices to access - size_t j = d + 1; - size_t k; - while(j) - { --j; - for(k = 0; k <= j; k++) - { - px[j-k] += azmul(pz[j], y[k]); - py[k] += azmul(pz[j], x[j-k]); - } - } -} -// --------------------------- Mulpv ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = MulpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x * y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op -*/ - -template -inline void forward_mulpv_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(MulpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(MulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to arguments and result - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - // Paraemter value - Base x = parameter[ arg[0] ]; - - for(size_t d = p; d <= q; d++) - z[d] = x * y[d]; -} -/*! -Multiple directions forward mode Taylor coefficients for op = MulpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x * y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op_dir -*/ - -template -inline void forward_mulpv_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(MulpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(MulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to arguments and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - size_t m = (q-1) * r + 1; - Base* y = taylor + arg[1] * num_taylor_per_var + m; - Base* z = taylor + i_z * num_taylor_per_var + m; - - // Paraemter value - Base x = parameter[ arg[0] ]; - - for(size_t ell = 0; ell < r; ell++) - z[ell] = x * y[ell]; -} -/*! -Compute zero order forward mode Taylor coefficient for result of op = MulpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x * y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op_0 -*/ - -template -inline void forward_mulpv_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(MulpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(MulpvOp) == 1 ); - - // Paraemter value - Base x = parameter[ arg[0] ]; - - // Taylor coefficients corresponding to arguments and result - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = x * y[0]; -} - -/*! -Compute reverse mode partial derivative for result of op = MulpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x * y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails reverse_binary_op -*/ - -template -inline void reverse_mulpv_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(MulpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(MulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Arguments - Base x = parameter[ arg[0] ]; - - // Partial derivatives corresponding to arguments and result - Base* py = partial + arg[1] * nc_partial; - Base* pz = partial + i_z * nc_partial; - - // number of indices to access - size_t j = d + 1; - while(j) - { --j; - py[j] += azmul(pz[j], x); - } -} - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/near_equal_ext.hpp b/ct_core/include/ct/external/cppad/local/near_equal_ext.hpp deleted file mode 100644 index 2b3afb10e..000000000 --- a/ct_core/include/ct/external/cppad/local/near_equal_ext.hpp +++ /dev/null @@ -1,189 +0,0 @@ -// $Id: near_equal_ext.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_NEAR_EQUAL_EXT_HPP -# define CPPAD_NEAR_EQUAL_EXT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin NearEqualExt$$ -$spell - cout - endl - Microsoft - std - Cpp - namespace - const - bool -$$ - -$section Compare AD and Base Objects for Nearly Equal$$ -$mindex NearEqual with$$ - - -$head Syntax$$ -$icode%b% = NearEqual(%x%, %y%, %r%, %a%)%$$ - - -$head Purpose$$ -The routine $cref NearEqual$$ determines if two objects of -the same type are nearly. -This routine is extended to the case where one object can have type -$icode Type$$ while the other can have type -$codei%AD<%Type%>%$$ or -$codei%AD< std::complex<%Type%> >%$$. - -$head x$$ -The arguments $icode x$$ -has one of the following possible prototypes: -$codei% - const %Type% &%x% - const AD<%Type%> &%x% - const AD< std::complex<%Type%> > &%x% -%$$ - -$head y$$ -The arguments $icode y$$ -has one of the following possible prototypes: -$codei% - const %Type% &%y% - const AD<%Type%> &%y% - const AD< std::complex<%Type%> > &%x% -%$$ - - -$head r$$ -The relative error criteria $icode r$$ has prototype -$codei% - const %Type% &%r% -%$$ -It must be greater than or equal to zero. -The relative error condition is defined as: -$latex \[ - \frac{ | x - y | } { |x| + |y| } \leq r -\] $$ - -$head a$$ -The absolute error criteria $icode a$$ has prototype -$codei% - const %Type% &%a% -%$$ -It must be greater than or equal to zero. -The absolute error condition is defined as: -$latex \[ - | x - y | \leq a -\] $$ - -$head b$$ -The return value $icode b$$ has prototype -$codei% - bool %b% -%$$ -If either $icode x$$ or $icode y$$ is infinite or not a number, -the return value is false. -Otherwise, if either the relative or absolute error -condition (defined above) is satisfied, the return value is true. -Otherwise, the return value is false. - -$head Type$$ -The type $icode Type$$ must be a -$cref NumericType$$. -The routine $cref CheckNumericType$$ will generate -an error message if this is not the case. -If $icode a$$ and $icode b$$ have type $icode Type$$, -the following operation must be defined -$table -$bold Operation$$ $cnext - $bold Description$$ $rnext -$icode%a% <= %b%$$ $cnext - less that or equal operator (returns a $code bool$$ object) -$tend - -$head Operation Sequence$$ -The result of this operation is not an -$cref/AD of Base/glossary/AD of Base/$$ object. -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Example$$ -$children% - example/near_equal_ext.cpp -%$$ -The file $cref near_equal_ext.cpp$$ contains an example -and test of this extension of $cref NearEqual$$. -It return true if it succeeds and false otherwise. - -$end - -*/ -// BEGIN CppAD namespace -namespace CppAD { -// ------------------------------------------------------------------------ - -// fold into base type and then use -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual( -const AD &x, const AD &y, const Base &r, const Base &a) -{ return NearEqual(x.value_, y.value_, r, a); -} - -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual( -const Base &x, const AD &y, const Base &r, const Base &a) -{ return NearEqual(x, y.value_, r, a); -} - -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual( -const AD &x, const Base &y, const Base &r, const Base &a) -{ return NearEqual(x.value_, y, r, a); -} - -// fold into AD type and then use cases above -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual( - const VecAD_reference &x, const VecAD_reference &y, - const Base &r, const Base &a) -{ return NearEqual(x.ADBase(), y.ADBase(), r, a); -} -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual(const VecAD_reference &x, const AD &y, - const Base &r, const Base &a) -{ return NearEqual(x.ADBase(), y, r, a); -} -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual(const VecAD_reference &x, const Base &y, - const Base &r, const Base &a) -{ return NearEqual(x.ADBase(), y, r, a); -} -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual(const AD &x, const VecAD_reference &y, - const Base &r, const Base &a) -{ return NearEqual(x, y.ADBase(), r, a); -} -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool NearEqual(const Base &x, const VecAD_reference &y, - const Base &r, const Base &a) -{ return NearEqual(x, y.ADBase(), r, a); -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/num_skip.hpp b/ct_core/include/ct/external/cppad/local/num_skip.hpp deleted file mode 100644 index c1edaec87..000000000 --- a/ct_core/include/ct/external/cppad/local/num_skip.hpp +++ /dev/null @@ -1,103 +0,0 @@ -// $Id: num_skip.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_NUM_SKIP_HPP -# define CPPAD_NUM_SKIP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin number_skip$$ -$spell - optimizer - var - taylor_ -$$ - - -$section Number of Variables that Can be Skipped$$ -$mindex number_skip$$ - -$head Syntax$$ -$icode%n% = %f%.number_skip()%$$ - -$subhead See Also$$ -$cref seq_property$$ - -$head Purpose$$ -The $cref/conditional expressions/CondExp/$$ use either the -$cref/if_true/CondExp/$$ or $cref/if_false/CondExp/$$. -This leads to the fact that some terms only need to be evaluated -depending on the value of the comparison in the conditional expression. -The $cref optimize$$ option is capable of detecting some of these -case and determining variables that can be skipped. -This routine returns the number such variables. - -$head n$$ -The return value $icode n$$ has type $code size_t$$ -is the number of variables that the optimizer has determined can be skipped -(given the independent variable values specified by the previous call to -$cref/f.Forward/Forward/$$ for order zero). - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ - -$children% - example/number_skip.cpp -%$$ -$head Example$$ -The file $cref number_skip.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -// This routine is not const becasue it runs through the operations sequence -// 2DO: compute this value during zero order forward operations. -template -size_t ADFun::number_skip(void) -{ // must pass through operation sequence to map operations to variables - OpCode op; - size_t i_op; - size_t i_var; - const addr_t* arg; - - // number of variables skipped - size_t n_skip = 0; - - // start playback - play_.forward_start(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN(op == BeginOp) - while(op != EndOp) - { // next op - play_.forward_next(op, arg, i_op, i_var); - if( op == CSumOp) - play_.forward_csum(op, arg, i_op, i_var); - else if (op == CSkipOp) - play_.forward_cskip(op, arg, i_op, i_var); - // - if( cskip_op_[i_op] ) - n_skip += NumRes(op); - } - return n_skip; -} - -} // END CppAD namespace - - -# endif diff --git a/ct_core/include/ct/external/cppad/local/numeric_limits.hpp b/ct_core/include/ct/external/cppad/local/numeric_limits.hpp deleted file mode 100644 index cb41ea3e0..000000000 --- a/ct_core/include/ct/external/cppad/local/numeric_limits.hpp +++ /dev/null @@ -1,199 +0,0 @@ -// $Id$ -# ifndef CPPAD_NUMERIC_LIMITS_HPP -# define CPPAD_NUMERIC_LIMITS_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ------------------------------------------------------------------------------- -$begin numeric_limits$$ -$spell - std - eps - CppAD - namespace - const -$$ - -$section Numeric Limits For an AD and Base Types$$ - -$head Syntax$$ -$icode%eps% = numeric_limits<%Float%>::epsilon() -%$$ -$icode%min% = numeric_limits<%Float%>::min() -%$$ -$icode%max% = numeric_limits<%Float%>::max() -%$$ -$icode%nan% = numeric_limits<%Float%>::quiet_NaN() -%$$ - -$head CppAD::numeric_limits$$ -These functions and have the prototype -$codei% - static %Float% CppAD::numeric_limits<%Float%>::%fun%(%void%) -%$$ -where $icode fun$$ is -$code epsilon$$, $code min$$, $code max$$, and $code quiet_NaN$$. - -$head std::numeric_limits$$ -CppAD does not use a specialization of $code std::numeric_limits$$ -because this would be to restrictive. -The C++ standard specifies that Non-fundamental standard -types, such as -$cref/std::complex/base_complex.hpp/$$ shall not have specializations -of $code std::numeric_limits$$; see Section 18.2 of -ISO/IEC 14882:1998(E). -In addition, since C++11, a only literal types can have a specialization -of $code std::numeric_limits$$. - -$head Float$$ -These functions are defined for all $codei%AD<%Base%>%$$, -and for all corresponding $icode Base$$ types; -see $icode Base$$ type $cref base_limits$$. - -$head epsilon$$ -The result $icode eps$$ is equal to machine epsilon and has prototype -$codei% - %Float% %eps% -%$$ -The file $cref num_limits.cpp$$ -tests the value $icode eps$$ by checking that the following are true -$codei% - 1 != 1 + %eps% - 1 == 1 + %eps% / 2 -%$$ -where all the values, and calculations, are done with the precision -corresponding to $icode Float$$. - -$head min$$ -The result $icode min$$ is equal to -the minimum positive normalized value and has prototype -$codei% - %Float% %min% -%$$ -The file $cref num_limits.cpp$$ -tests the value $icode min$$ by checking that the following are true -$codei% - abs( ((%min% / 100) * 100) / %min% - 1 ) > 3 * %eps% - abs( ((%min% * 100) / 100) / %min% - 1 ) < 3 * %eps% -%$$ -where all the values, and calculations, are done with the precision -corresponding to $icode Float$$. - -$head max$$ -The result $icode max$$ is equal to -the maximum finite value and has prototype -$codei% - %Float% %max% -%$$ -The file $cref num_limits.cpp$$ -tests the value $icode max$$ by checking that the following are true -$codei% - abs( ((%max% * 100) / 100) / %max% - 1 ) > 3 * %eps% - abs( ((%max% / 100) * 100) / %max% - 1 ) < 3 * %eps% -%$$ -where all the values, and calculations, are done with the precision -corresponding to $icode Float$$. - -$head quiet_NaN$$ -The result $icode nan$$ is not a number and has prototype -$codei% - %Float% %nan% -%$$ -The file $cref num_limits.cpp$$ -tests the value $icode nan$$ by checking that the following is true -$codei% - %nan% != %nan% -%$$ - - -$head Example$$ -$children% - example/num_limits.cpp -%$$ -The file -$cref num_limits.cpp$$ -contains an example and test of these functions. - -$end ------------------------------------------------------------------------------- -*/ -# include - -# include -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file numeric_limits.hpp -File that defines CppAD numeric_limits for AD types -*/ - -/// Default value for all undefined numeric_limits types -template -class numeric_limits { -public: - /// machine epsilon - static Float epsilon(void) - { CPPAD_ASSERT_KNOWN( - false, - "numeric_limits::epsilon() is not specialized for this Float" - ); - return Float(0); - } - /// minimum positive normalized value - static Float min(void) - { CPPAD_ASSERT_KNOWN( - false, - "numeric_limits::min() is not specialized for this Float" - ); - return Float(0); - } - /// maximum finite value - static Float max(void) - { CPPAD_ASSERT_KNOWN( - false, - "numeric_limits::max() is not specialized for this Float" - ); - return Float(0); - } - /// not a number - static Float quiet_NaN(void) - { CPPAD_ASSERT_KNOWN( - false, - "numeric_limits::quiet_NaN() is not specialized for this Float" - ); - return Float(0); - } -}; - -/// Partial specialization that defines limits for for all AD types -template -class numeric_limits< AD > { -public: - /// machine epsilon - static AD epsilon(void) - { return AD( numeric_limits::epsilon() ); } - /// minimum positive normalized value - static AD min(void) - { return AD( numeric_limits::min() ); } - /// maximum finite value - static AD max(void) - { return AD( numeric_limits::max() ); } - /// note a number - static AD quiet_NaN(void) - { return AD( numeric_limits::quiet_NaN() ); } -}; - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/old_atomic.hpp b/ct_core/include/ct/external/cppad/local/old_atomic.hpp deleted file mode 100644 index 8765b24d7..000000000 --- a/ct_core/include/ct/external/cppad/local/old_atomic.hpp +++ /dev/null @@ -1,1086 +0,0 @@ -// $Id: old_atomic.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_OLD_ATOMIC_HPP -# define CPPAD_OLD_ATOMIC_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin old_atomic$$ -$spell - hes - std - Jacobian - jac - Tvector - afun - vx - vy - bool - namespace - CppAD - const - Taylor - tx - ty - px - py -$$ - -$section User Defined Atomic AD Functions$$ -$mindex operation old_atomic$$ - -$head Deprecated 2013-05-27$$ -Using $code CPPAD_USER_ATOMIC$$ has been deprecated. -Use $cref atomic_base$$ instead. - -$head Syntax Function$$ -$codei%CPPAD_USER_ATOMIC(%afun%, %Tvector%, %Base%, - %forward%, %reverse%, %for_jac_sparse%, %rev_jac_sparse%, %rev_hes_sparse% -) -%$$ - -$subhead Use Function$$ -$icode%afun%(%id%, %ax%, %ay%) -%$$ - -$subhead Callback Routines$$ -$icode%ok% = %forward%(%id%, %k%, %n%, %m%, %vx%, %vy%, %tx%, %ty%) -%$$ -$icode%ok% = %reverse%(%id%, %k%, %n%, %m%, %tx%, %ty%, %px%, %py%) -%$$ -$icode%ok% = %for_jac_sparse%(%id%, %n%, %m%, %q%, %r%, %s%) -%$$ -$icode%ok% = %rev_jac_sparse%(%id%, %n%, %m%, %q%, %r%, %s%) -%$$ -$icode%ok% = %rev_hes_sparse%(%id%, %n%, %m%, %q%, %r%, %s%, %t%, %u%, %v%) -%$$ - -$subhead Free Static Memory$$ -$codei%user_atomic<%Base%>::clear()%$$ - -$head Purpose$$ -In some cases, the user knows how to compute the derivative -of a function -$latex \[ - y = f(x) \; {\rm where} \; f : B^n \rightarrow B^m -\] $$ -more efficiently than by coding it using $codei%AD<%Base%>%$$ -$cref/atomic/glossary/Operation/Atomic/$$ operations -and letting CppAD do the rest. -In this case, $code CPPAD_USER_ATOMIC$$ can be used -add the user code for $latex f(x)$$, and its derivatives, -to the set of $codei%AD<%Base%>%$$ atomic operations. -$pre - -$$ -Another possible purpose is to reduce the size of the tape; -see $cref/use AD/old_atomic/Example/Use AD/$$ - -$head Partial Implementation$$ -The routines -$cref/forward/old_atomic/forward/$$, -$cref/reverse/old_atomic/reverse/$$, -$cref/for_jac_sparse/old_atomic/for_jac_sparse/$$, -$cref/rev_jac_sparse/old_atomic/rev_jac_sparse/$$, and -$cref/rev_hes_sparse/old_atomic/rev_hes_sparse/$$, -must be defined by the user. -The $icode forward$$ the routine, -for the case $icode%k% = 0%$$, must be implemented. -Functions with the correct prototype, -that just return $code false$$, -can be used for the other cases -(unless they are required by your calculations). -For example, you need not implement -$icode forward$$ for the case $icode%k% == 2%$$ until you require -forward mode calculation of second derivatives. - -$head CPPAD_USER_ATOMIC$$ -The macro -$codei% -CPPAD_USER_ATOMIC(%afun%, %Tvector%, %Base%, - %forward%, %reverse%, %for_jac_sparse%, %rev_jac_sparse%, %rev_hes_sparse% -) -%$$ -defines the $codei%AD<%Base%>%$$ routine $icode afun$$. -This macro can be placed within a namespace -(not the $code CppAD$$ namespace) -but must be outside of any routine. - -$subhead Tvector$$ -The macro argument $icode Tvector$$ must be a -$cref/simple vector template class/SimpleVector/$$. -It determines the type of vectors used as arguments to the routine -$icode afun$$. - -$subhead Base$$ -The macro argument $icode Base$$ specifies the -$cref/base type/base_require/$$ -corresponding to $codei%AD<%Base>%$$ operation sequences. -Calling the routine $icode afun$$ will add the operator defined -by this macro to an $codei%AD<%Base>%$$ operation sequence. - -$head ok$$ -For all routines documented below, -the return value $icode ok$$ has prototype -$codei% - bool %ok% -%$$ -If it is $code true$$, the corresponding evaluation succeeded, -otherwise it failed. - -$head id$$ -For all routines documented below, -the argument $icode id$$ has prototype -$codei% - size_t %id% -%$$ -Its value in all other calls is the same as in the corresponding -call to $icode afun$$. -It can be used to store and retrieve extra information about -a specific call to $icode afun$$. - -$head k$$ -For all routines documented below, the argument $icode k$$ has prototype -$codei% - size_t %k% -%$$ -The value $icode%k%$$ is the order of the Taylor coefficient that -we are evaluating ($cref/forward/old_atomic/forward/$$) -or taking the derivative of ($cref/reverse/old_atomic/reverse/$$). - -$head n$$ -For all routines documented below, -the argument $icode n$$ has prototype -$codei% - size_t %n% -%$$ -It is the size of the vector $icode ax$$ in the corresponding call to -$icode%afun%(%id%, %ax%, %ay%)%$$; i.e., -the dimension of the domain space for $latex y = f(x)$$. - -$head m$$ -For all routines documented below, the argument $icode m$$ has prototype -$codei% - size_t %m% -%$$ -It is the size of the vector $icode ay$$ in the corresponding call to -$icode%afun%(%id%, %ax%, %ay%)%$$; i.e., -the dimension of the range space for $latex y = f(x)$$. - -$head tx$$ -For all routines documented below, -the argument $icode tx$$ has prototype -$codei% - const CppAD::vector<%Base%>& %tx% -%$$ -and $icode%tx%.size() >= (%k% + 1) * %n%$$. -For $latex j = 0 , \ldots , n-1$$ and $latex \ell = 0 , \ldots , k$$, -we use the Taylor coefficient notation -$latex \[ -\begin{array}{rcl} - x_j^\ell & = & tx [ j * ( k + 1 ) + \ell ] - \\ - X_j (t) & = & x_j^0 + x_j^1 t^1 + \cdots + x_j^k t^k -\end{array} -\] $$ -If $icode%tx%.size() > (%k% + 1) * %n%$$, -the other components of $icode tx$$ are not specified and should not be used. -Note that superscripts represent an index for $latex x_j^\ell$$ -and an exponent for $latex t^\ell$$. -Also note that the Taylor coefficients for $latex X(t)$$ correspond -to the derivatives of $latex X(t)$$ at $latex t = 0$$ in the following way: -$latex \[ - x_j^\ell = \frac{1}{ \ell ! } X_j^{(\ell)} (0) -\] $$ - -$head ty$$ -In calls to $cref/forward/old_atomic/forward/$$, -the argument $icode ty$$ has prototype -$codei% - CppAD::vector<%Base%>& %ty% -%$$ -while in calls to $cref/reverse/old_atomic/reverse/$$ it has prototype -$codei% - const CppAD::vector<%Base%>& %ty% -%$$ -For all calls, $icode%tx%.size() >= (%k% + 1) * %m%$$. -For $latex i = 0 , \ldots , m-1$$ and $latex \ell = 0 , \ldots , k$$, -we use the Taylor coefficient notation -$latex \[ -\begin{array}{rcl} - y_i^\ell & = & ty [ i * ( k + 1 ) + \ell ] - \\ - Y_i (t) & = & y_i^0 + y_i^1 t^1 + \cdots + y_i^k t^k + o ( t^k ) -\end{array} -\] $$ -where $latex o( t^k ) / t^k \rightarrow 0$$ as $latex t \rightarrow 0$$. -If $icode%ty%.size() > (%k% + 1) * %m%$$, -the other components of $icode ty$$ are not specified and should not be used. -Note that superscripts represent an index for $latex y_j^\ell$$ -and an exponent for $latex t^\ell$$. -Also note that the Taylor coefficients for $latex Y(t)$$ correspond -to the derivatives of $latex Y(t)$$ at $latex t = 0$$ in the following way: -$latex \[ - y_j^\ell = \frac{1}{ \ell ! } Y_j^{(\ell)} (0) -\] $$ - -$subhead forward$$ -In the case of $icode forward$$, -for $latex i = 0 , \ldots , m-1$$, $latex ty[ i *( k + 1) + k ]$$ is an output -and all the other components of $icode ty$$ are inputs. - -$subhead reverse$$ -In the case of $icode reverse$$, -all the components of $icode ty$$ are inputs. - -$head afun$$ -The macro argument $icode afun$$, -is the name of the AD function corresponding to this atomic -operation (as it is used in the source code). -CppAD uses the other functions, -where the arguments are vectors with elements of type $icode Base$$, -to implement the function -$codei% - %afun%(%id%, %ax%, %ay%) -%$$ -where the argument are vectors with elements of type $codei%AD<%Base%>%$$. - -$subhead ax$$ -The $icode afun$$ argument $icode ax$$ has prototype -$codei% - const %Tvector%< AD<%Base%> >& %ax% -%$$ -It is the argument vector $latex x \in B^n$$ -at which the $codei%AD<%Base%>%$$ version of -$latex y = f(x)$$ is to be evaluated. -The dimension of the domain space for $latex y = f (x)$$ -is specified by $cref/n/old_atomic/n/$$ $codei%= %ax%.size()%$$, -which must be greater than zero. - -$subhead ay$$ -The $icode afun$$ result $icode ay$$ has prototype -$codei% - %Tvector%< AD<%Base%> >& %ay% -%$$ -The input values of its elements -are not specified (must not matter). -Upon return, it is the $codei%AD<%Base%>%$$ version of the -result vector $latex y = f(x)$$. -The dimension of the range space for $latex y = f (x)$$ -is specified by $cref/m/old_atomic/m/$$ $codei%= %ay%.size()%$$, -which must be greater than zero. - -$subhead Parallel Mode$$ -The first call to -$codei% - %afun%(%id%, %ax%, %ay%) -%$$ -must not be in $cref/parallel/ta_in_parallel/$$ mode. -In addition, the -$cref/old_atomic clear/old_atomic/clear/$$ -routine cannot be called while in parallel mode. - -$head forward$$ -The macro argument $icode forward$$ is a -user defined function -$codei% - %ok% = %forward%(%id%, %k%, %n%, %m%, %vx%, %vy%, %tx%, %ty%) -%$$ -that computes results during a $cref/forward/Forward/$$ mode sweep. -For this call, we are given the Taylor coefficients in $icode tx$$ -form order zero through $icode k$$, -and the Taylor coefficients in $icode ty$$ with order less than $icode k$$. -The $icode forward$$ routine computes the -$icode k$$ order Taylor coefficients for $latex y$$ using the definition -$latex Y(t) = f[ X(t) ]$$. -For example, for $latex i = 0 , \ldots , m-1$$, -$latex \[ -\begin{array}{rcl} -y_i^0 & = & Y(0) - = f_i ( x^0 ) -\\ -y_i^1 & = & Y^{(1)} ( 0 ) - = f_i^{(1)} ( x^0 ) X^{(1)} ( 0 ) - = f_i^{(1)} ( x^0 ) x^1 -\\ -y_i^2 -& = & \frac{1}{2 !} Y^{(2)} (0) -\\ -& = & \frac{1}{2} X^{(1)} (0)^\R{T} f_i^{(2)} ( x^0 ) X^{(1)} ( 0 ) - + \frac{1}{2} f_i^{(1)} ( x^0 ) X^{(2)} ( 0 ) -\\ -& = & \frac{1}{2} (x^1)^\R{T} f_i^{(2)} ( x^0 ) x^1 - + f_i^{(1)} ( x^0 ) x^2 -\end{array} -\] $$ -Then, for $latex i = 0 , \ldots , m-1$$, it sets -$latex \[ - ty [ i * (k + 1) + k ] = y_i^k -\] $$ -The other components of $icode ty$$ must be left unchanged. - -$subhead Usage$$ -This routine is used, -with $icode%vx%.size() > 0%$$ and $icode%k% == 0%$$, -by calls to $icode afun$$. -It is used, -with $icode%vx%.size() = 0%$$ and -$icode k$$ equal to the order of the derivative begin computed, -by calls to $cref/forward/forward_order/$$. - -$subhead vx$$ -The $icode forward$$ argument $icode vx$$ has prototype -$codei% - const CppAD::vector& %vx% -%$$ -The case $icode%vx%.size() > 0%$$ occurs -once for each call to $icode afun$$, -during the call, -and before any of the other callbacks corresponding to that call. -Hence such a call can be used to cache information attached to -the corresponding $icode id$$ -(such as the elements of $icode vx$$). -If $icode%vx%.size() > 0%$$ then -$icode%k% == 0%$$, -$icode%vx%.size() >= %n%$$, and -for $latex j = 0 , \ldots , n-1$$, -$icode%vx%[%j%]%$$ is true if and only if -$icode%ax%[%j%]%$$ is a $cref/variable/glossary/Variable/$$. -$pre - -$$ -If $icode%vx%.size() == 0%$$, -then $icode%vy%.size() == 0%$$ and neither of these vectors -should be used. - -$subhead vy$$ -The $icode forward$$ argument $icode vy$$ has prototype -$codei% - CppAD::vector& %vy% -%$$ -If $icode%vy%.size() == 0%$$, it should not be used. -Otherwise, -$icode%k% == 0%$$ and $icode%vy%.size() >= %m%$$. -The input values of the elements of $icode vy$$ -are not specified (must not matter). -Upon return, for $latex j = 0 , \ldots , m-1$$, -$icode%vy%[%i%]%$$ is true if and only if -$icode%ay%[%j%]%$$ is a variable. -(CppAD uses $icode vy$$ to reduce the necessary computations.) - -$head reverse$$ -The macro argument $icode reverse$$ -is a user defined function -$codei% - %ok% = %reverse%(%id%, %k%, %n%, %m%, %tx%, %ty%, %px%, %py%) -%$$ -that computes results during a $cref/reverse/Reverse/$$ mode sweep. -The input value of the vectors $icode tx$$ and $icode ty$$ -contain Taylor coefficient, up to order $icode k$$, -for $latex X(t)$$ and $latex Y(t)$$ respectively. -We use the $latex \{ x_j^\ell \}$$ and $latex \{ y_i^\ell \}$$ -to denote these Taylor coefficients where the implicit range indices are -$latex i = 0 , \ldots , m-1$$, -$latex j = 0 , \ldots , n-1$$, -$latex \ell = 0 , \ldots , k$$. -Using the calculations done by $cref/forward/old_atomic/forward/$$, -the Taylor coefficients $latex \{ y_i^\ell \}$$ are a function of the Taylor -coefficients for $latex \{ x_j^\ell \}$$; i.e., given $latex y = f(x)$$ -we define the function -$latex F : B^{n \times (k+1)} \rightarrow B^{m \times (k+1)}$$ by -$latex \[ -y_i^\ell = F_i^\ell ( \{ x_j^\ell \} ) -\] $$ -We use $latex G : B^{m \times (k+1)} \rightarrow B$$ -to denote an arbitrary scalar valued function of the Taylor coefficients for -$latex Y(t)$$ and write $latex z = G( \{ y_i^\ell \} )$$. -The $code reverse$$ routine -is given the derivative of $latex z$$ with respect to -$latex \{ y_i^\ell \}$$ and computes its derivative with respect -to $latex \{ x_j^\ell \}$$. - -$subhead Usage$$ -This routine is used, -with $icode%k% + 1%$$ equal to the order of the derivative being calculated, -by calls to $cref/reverse/reverse_any/$$. - -$subhead py$$ -The $icode reverse$$ argument $icode py$$ has prototype -$codei% - const CppAD::vector<%Base%>& %py% -%$$ -and $icode%py%.size() >= (%k% + 1) * %m%$$. -For $latex i = 0 , \ldots , m-1$$ and $latex \ell = 0 , \ldots , k$$, -$latex \[ - py[ i * (k + 1 ) + \ell ] = \partial G / \partial y_i^\ell -\] $$ -If $icode%py%.size() > (%k% + 1) * %m%$$, -the other components of $icode py$$ are not specified and should not be used. - -$subhead px$$ -We define the function -$latex \[ -H ( \{ x_j^\ell \} ) = G[ F( \{ x_j^\ell \} ) ] -\] $$ -The $icode reverse$$ argument $icode px$$ has prototype -$codei% - CppAD::vector<%Base%>& %px% -%$$ -and $icode%px%.size() >= (%k% + 1) * %n%$$. -The input values of the elements of $icode px$$ -are not specified (must not matter). -Upon return, -for $latex j = 0 , \ldots , n-1$$ and $latex p = 0 , \ldots , k$$, -$latex \[ -\begin{array}{rcl} -px [ j * (k + 1) + p ] & = & \partial H / \partial x_j^p -\\ -& = & -( \partial G / \partial \{ y_i^\ell \} ) - ( \partial \{ y_i^\ell \} / \partial x_j^p ) -\\ -& = & -\sum_{i=0}^{m-1} \sum_{\ell=0}^k -( \partial G / \partial y_i^\ell ) ( \partial y_i^\ell / \partial x_j^p ) -\\ -& = & -\sum_{i=0}^{m-1} \sum_{\ell=p}^k -py[ i * (k + 1 ) + \ell ] ( \partial F_i^\ell / \partial x_j^p ) -\end{array} -\] $$ -Note that we have used the fact that for $latex \ell < p$$, -$latex \partial F_i^\ell / \partial x_j^p = 0$$. -If $icode%px%.size() > (%k% + 1) * %n%$$, -the other components of $icode px$$ are not specified and should not be used. - -$head for_jac_sparse$$ -The macro argument $icode for_jac_sparse$$ -is a user defined function -$codei% - %ok% = %for_jac_sparse%(%id%, %n%, %m%, %q%, %r%, %s%) -%$$ -that is used to compute results during a forward Jacobian sparsity sweep. -For a fixed $latex n \times q$$ matrix $latex R$$, -the Jacobian of $latex f( x + R * u)$$ with respect to $latex u \in B^q$$ is -$latex \[ - S(x) = f^{(1)} (x) * R -\] $$ -Given a $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for $latex R$$, -$icode for_jac_sparse$$ computes a sparsity pattern for $latex S(x)$$. - -$subhead Usage$$ -This routine is used by calls to $cref ForSparseJac$$. - -$subhead q$$ -The $icode for_jac_sparse$$ argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of columns in -$latex R \in B^{n \times q}$$ and the Jacobian -$latex S(x) \in B^{m \times q}$$. - -$subhead r$$ -The $icode for_jac_sparse$$ argument $icode r$$ has prototype -$codei% - const CppAD::vector< std::set >& %r% -%$$ -and $icode%r%.size() >= %n%$$. -For $latex j = 0 , \ldots , n-1$$, -all the elements of $icode%r%[%j%]%$$ are between -zero and $icode%q%-1%$$ inclusive. -This specifies a sparsity pattern for the matrix $latex R$$. - -$subhead s$$ -The $icode for_jac_sparse$$ return value $icode s$$ has prototype -$codei% - CppAD::vector< std::set >& %s% -%$$ -and $icode%s%.size() >= %m%%$$. -The input values of its sets -are not specified (must not matter). Upon return -for $latex i = 0 , \ldots , m-1$$, -all the elements of $icode%s%[%i%]%$$ are between -zero and $icode%q%-1%$$ inclusive. -This represents a sparsity pattern for the matrix $latex S(x)$$. - -$head rev_jac_sparse$$ -The macro argument $icode rev_jac_sparse$$ -is a user defined function -$codei% - %ok% = %rev_jac_sparse%(%id%, %n%, %m%, %q%, %r%, %s%) -%$$ -that is used to compute results during a reverse Jacobian sparsity sweep. -For a fixed $latex q \times m$$ matrix $latex S$$, -the Jacobian of $latex S * f( x )$$ with respect to $latex x \in B^n$$ is -$latex \[ - R(x) = S * f^{(1)} (x) -\] $$ -Given a $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for $latex S$$, -$icode rev_jac_sparse$$ computes a sparsity pattern for $latex R(x)$$. - -$subhead Usage$$ -This routine is used by calls to $cref RevSparseJac$$ -and to $cref optimize$$. - - -$subhead q$$ -The $icode rev_jac_sparse$$ argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of rows in -$latex S \in B^{q \times m}$$ and the Jacobian -$latex R(x) \in B^{q \times n}$$. - -$subhead s$$ -The $icode rev_jac_sparse$$ argument $icode s$$ has prototype -$codei% - const CppAD::vector< std::set >& %s% -%$$ -and $icode%s%.size() >= %m%$$. -For $latex i = 0 , \ldots , m-1$$, -all the elements of $icode%s%[%i%]%$$ -are between zero and $icode%q%-1%$$ inclusive. -This specifies a sparsity pattern for the matrix $latex S^\R{T}$$. - -$subhead r$$ -The $icode rev_jac_sparse$$ return value $icode r$$ has prototype -$codei% - CppAD::vector< std::set >& %r% -%$$ -and $icode%r%.size() >= %n%$$. -The input values of its sets -are not specified (must not matter). -Upon return for $latex j = 0 , \ldots , n-1$$, -all the elements of $icode%r%[%j%]%$$ -are between zero and $icode%q%-1%$$ inclusive. -This represents a sparsity pattern for the matrix $latex R(x)^\R{T}$$. - -$head rev_hes_sparse$$ -The macro argument $icode rev_hes_sparse$$ -is a user defined function -$codei% - %ok% = %rev_hes_sparse%(%id%, %n%, %m%, %q%, %r%, %s%, %t%, %u%, %v%) -%$$ -There is an unspecified scalar valued function -$latex g : B^m \rightarrow B$$. -Given a sparsity pattern for $latex R$$ -and information about the function $latex z = g(y)$$, -this routine computes the sparsity pattern for -$latex \[ - V(x) = (g \circ f)^{(2)}( x ) R -\] $$ - -$subhead Usage$$ -This routine is used by calls to $cref RevSparseHes$$. - -$subhead q$$ -The $icode rev_hes_sparse$$ argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of columns in the sparsity patterns. - -$subhead r$$ -The $icode rev_hes_sparse$$ argument $icode r$$ has prototype -$codei% - const CppAD::vector< std::set >& %r% -%$$ -and $icode%r%.size() >= %n%$$. -For $latex j = 0 , \ldots , n-1$$, -all the elements of $icode%r%[%j%]%$$ are between -zero and $icode%q%-1%$$ inclusive. -This specifies a sparsity pattern for the matrix $latex R \in B^{n \times q}$$. - -$subhead s$$ -The $icode rev_hes_sparse$$ argument $icode s$$ has prototype -$codei% - const CppAD::vector& %s% -%$$ -and $icode%s%.size() >= %m%$$. -This specifies a sparsity pattern for the matrix -$latex S(x) = g^{(1)} (y) \in B^{1 \times m}$$. - -$subhead t$$ -The $icode rev_hes_sparse$$ argument $icode t$$ has prototype -$codei% - CppAD::vector& %t% -%$$ -and $icode%t%.size() >= %n%$$. -The input values of its elements -are not specified (must not matter). -Upon return it represents a sparsity pattern for the matrix -$latex T(x) \in B^{1 \times n}$$ defined by -$latex \[ -T(x) = (g \circ f)^{(1)} (x) = S(x) * f^{(1)} (x) -\] $$ - -$subhead u$$ -The $icode rev_hes_sparse$$ argument $icode u$$ has prototype -$codei% - const CppAD::vector< std::set >& %u% -%$$ -and $icode%u%.size() >= %m%$$. -For $latex i = 0 , \ldots , m-1$$, -all the elements of $icode%u%[%i%]%$$ -are between zero and $icode%q%-1%$$ inclusive. -This specifies a sparsity pattern -for the matrix $latex U(x) \in B^{m \times q}$$ defined by -$latex \[ -\begin{array}{rcl} -U(x) -& = & -\partial_u \{ \partial_y g[ y + f^{(1)} (x) R u ] \}_{u=0} -\\ -& = & -\partial_u \{ g^{(1)} [ y + f^{(1)} (x) R u ] \}_{u=0} -\\ -& = & -g^{(2)} (y) f^{(1)} (x) R -\end{array} -\] $$ - -$subhead v$$ -The $icode rev_hes_sparse$$ argument $icode v$$ has prototype -$codei% - CppAD::vector< std::set >& %v% -%$$ -and $icode%v%.size() >= %n%$$. -The input values of its elements -are not specified (must not matter). -Upon return, for $latex j = 0, \ldots , n-1$$, -all the elements of $icode%v%[%j%]%$$ -are between zero and $icode%q%-1%$$ inclusive. -This represents a sparsity pattern for the matrix -$latex V(x) \in B^{n \times q}$$ defined by -$latex \[ -\begin{array}{rcl} -V(x) -& = & -\partial_u [ \partial_x (g \circ f) ( x + R u ) ]_{u=0} -\\ -& = & -\partial_u [ (g \circ f)^{(1)}( x + R u ) ]_{u=0} -\\ -& = & -(g \circ f)^{(2)}( x ) R -\\ -& = & -f^{(1)} (x)^\R{T} g^{(2)} ( y ) f^{(1)} (x) R -+ -\sum_{i=1}^m [ g^{(1)} (y) ]_i \; f_i^{(2)} (x) R -\\ -& = & -f^{(1)} (x)^\R{T} U(x) -+ -\sum_{i=1}^m S(x)_i \; f_i^{(2)} (x) R -\end{array} -\] $$ - -$head clear$$ -User atomic functions hold onto static work space in order to -increase speed by avoiding system memory allocation calls. -The function call $codei% - user_atomic<%Base%>::clear() -%$$ -makes to work space $cref/available/ta_available/$$ to -for other uses by the same thread. -This should be called when you are done using the -user atomic functions for a specific value of $icode Base$$. - -$subhead Restriction$$ -The user atomic $code clear$$ routine cannot be called -while in $cref/parallel/ta_in_parallel/$$ execution mode. - -$children% - test_more/old_reciprocal.cpp% - test_more/old_usead_1.cpp% - test_more/old_usead_2.cpp% - test_more/old_tan.cpp% - test_more/old_mat_mul.cpp -%$$ -$head Example$$ - -$subhead Simple$$ -The file $cref old_reciprocal.cpp$$ contains the simplest example and test -of a user atomic operation. - -$subhead Use AD$$ -The examples -$cref old_usead_1.cpp$$ and $cref old_usead_2.cpp$$ -use AD to compute the derivatives -inside a user defined atomic function. -This may have the advantage of reducing the size of the tape, because -a repeated section of code would only be taped once. - -$subhead Tangent Function$$ -The file $cref old_tan.cpp$$ contains an example and test -implementation of the tangent function as a user atomic operation. - -$subhead Matrix Multiplication$$ -The file $cref old_mat_mul.cpp$$ contains an example and test -implementation of matrix multiplication a a user atomic operation. - -$end ------------------------------------------------------------------------------- -*/ -# include -# include - -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file old_atomic.hpp -user defined atomic operations. -*/ - -/*! -\def CPPAD_USER_ATOMIC(afun, Tvector, - forward, reverse, for_jac_sparse, rev_jac_sparse, rev_hes_sparse -) -Defines the function afun(id, ax, ay) -where \c id is \c ax and \c ay are vectors with AD elements. - -\par Tvector -the Simple Vector template class for this function. - -\par Base -the base type for the atomic operation. - -\par afun -name of the CppAD defined function that corresponding to this operation. -Note that \c afun, preceeded by a pound sign, -is a version of \c afun with quotes arround it. - -\par forward -name of the user defined function that computes corresponding -results during forward mode. - -\par reverse -name of the user defined function that computes corresponding -results during reverse mode. - -\par for_jac_sparse -name of the user defined routine that computes corresponding -results during forward mode jacobian sparsity sweeps. - -\par rev_jac_sparse -name of the user defined routine that computes corresponding -results during reverse mode jacobian sparsity sweeps. - -\par rev_hes_sparse -name of the user defined routine that computes corresponding -results during reverse mode Hessian sparsity sweeps. - -\par memory allocation -Note that old_atomic is used as a static object, so its objects -do note get deallocated until the program terminates. -*/ -# define CPPAD_USER_ATOMIC( \ - afun , \ - Tvector , \ - Base , \ - forward , \ - reverse , \ - for_jac_sparse , \ - rev_jac_sparse , \ - rev_hes_sparse \ -) \ -inline void afun ( \ - size_t id , \ - const Tvector< CppAD::AD >& ax , \ - Tvector< CppAD::AD >& ay \ -) \ -{ CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; \ - static CppAD::old_atomic fun( \ - #afun , \ - forward , \ - reverse , \ - for_jac_sparse , \ - rev_jac_sparse , \ - rev_hes_sparse \ - ); \ - fun(id, ax, ay); \ -} - -/// link so that user_atomic::clear() still works -template class user_atomic : public atomic_base { -}; - -/*! -Class that actually implements the afun(id, ax, ay) calls. - -A new old_atomic object is generated each time the user invokes -the CPPAD_USER_ATOMIC macro; see static object in that macro. -*/ -template -class old_atomic : public atomic_base { -public: - /// disable old_atomic::clear(void) - static void clear(void) - { CPPAD_ASSERT_KNOWN( - false, - "Depreacted API uses user_atomic::clear()" - ); - } - /// type for user routine that computes forward mode results - typedef bool (*F) ( - size_t id , - size_t k , - size_t n , - size_t m , - const vector& vx , - vector& vy , - const vector& tx , - vector& ty - ); - /// type for user routine that computes reverse mode results - typedef bool (*R) ( - size_t id , - size_t k , - size_t n , - size_t m , - const vector& tx , - const vector& ty , - vector& px , - const vector& py - ); - /// type for user routine that computes forward mode Jacobian sparsity - typedef bool (*FJS) ( - size_t id , - size_t n , - size_t m , - size_t q , - const vector< std::set >& r , - vector< std::set >& s - ); - /// type for user routine that computes reverse mode Jacobian sparsity - typedef bool (*RJS) ( - size_t id , - size_t n , - size_t m , - size_t q , - vector< std::set >& r , - const vector< std::set >& s - ); - /// type for user routine that computes reverse mode Hessian sparsity - typedef bool (*RHS) ( - size_t id , - size_t n , - size_t m , - size_t q , - const vector< std::set >& r , - const vector& s , - vector& t , - const vector< std::set >& u , - vector< std::set >& v - ); -private: - /// id value corresponding to next virtual callback - size_t id_; - /// user's implementation of forward mode - const F f_; - /// user's implementation of reverse mode - const R r_; - /// user's implementation of forward jacobian sparsity calculations - const FJS fjs_; - /// user's implementation of reverse jacobian sparsity calculations - const RJS rjs_; - /// user's implementation of reverse Hessian sparsity calculations - const RHS rhs_; - -public: - /*! - Constructor called for each invocation of CPPAD_USER_ATOMIC. - - Put this object in the list of all objects for this class and set - the constant private data f_, r_, fjs_, rjs_, rhs_. - - \param afun - is the user's name for the AD version of this atomic operation. - - \param f - user routine that does forward mode calculations for this operation. - - \param r - user routine that does reverse mode calculations for this operation. - - \param fjs - user routine that does forward Jacobian sparsity calculations. - - \param rjs - user routine that does reverse Jacobian sparsity calculations. - - \param rhs - user routine that does reverse Hessian sparsity calculations. - - \par - This constructor can not be used in parallel mode because - atomic_base has this restriction. - */ - old_atomic(const char* afun, F f, R r, FJS fjs, RJS rjs, RHS rhs) : - atomic_base(afun) // name = afun - , f_(f) - , r_(r) - , fjs_(fjs) - , rjs_(rjs) - , rhs_(rhs) - { this->option( atomic_base::set_sparsity_enum ); - } - /*! - Implement the user call to afun(id, ax, ay). - - \tparam ADVector - A simple vector class with elements of type AD. - - \param id - extra information vector that is just passed through by CppAD, - and possibly used by user's routines. - - \param ax - is the argument vector for this call, - ax.size() determines the number of arguments. - - \param ay - is the result vector for this call, - ay.size() determines the number of results. - */ - template - void operator()(size_t id, const ADVector& ax, ADVector& ay) - { // call atomic_base function object - this->atomic_base::operator()(ax, ay, id); - return; - } - /*! - Store id for next virtual function callback - - \param id - id value corresponding to next virtual callback - */ - virtual void set_id(size_t id) - { id_ = id; } - /*! - Link from old_atomic to forward mode - - \copydetails atomic_base::forward - */ - virtual bool forward( - size_t p , - size_t q , - const vector& vx , - vector& vy , - const vector& tx , - vector& ty ) - { CPPAD_ASSERT_UNKNOWN( tx.size() % (q+1) == 0 ); - CPPAD_ASSERT_UNKNOWN( ty.size() % (q+1) == 0 ); - size_t n = tx.size() / (q+1); - size_t m = ty.size() / (q+1); - size_t i, j, k, ell; - - vector x(n * (q+1)); - vector y(m * (q+1)); - vector empty; - - // old_atomic interface can only handel one order at a time - // so must just throuh hoops to get multiple orders at one time. - bool ok = true; - for(k = p; k <= q; k++) - { for(j = 0; j < n; j++) - for(ell = 0; ell <= k; ell++) - x[ j * (k+1) + ell ] = tx[ j * (q+1) + ell ]; - for(i = 0; i < m; i++) - for(ell = 0; ell < k; ell++) - y[ i * (k+1) + ell ] = ty[ i * (q+1) + ell ]; - if( k == 0 ) - ok &= f_(id_, k, n, m, vx, vy, x, y); - else - ok &= f_(id_, k, n, m, empty, empty, x, y); - for(i = 0; i < m; i++) - ty[ i * (q+1) + k ] = y[ i * (k+1) + k]; - } - return ok; - } - /*! - Link from old_atomic to reverse mode - - \copydetails atomic_base::reverse - */ - virtual bool reverse( - size_t q , - const vector& tx , - const vector& ty , - vector& px , - const vector& py ) - { CPPAD_ASSERT_UNKNOWN( tx.size() % (q+1) == 0 ); - CPPAD_ASSERT_UNKNOWN( ty.size() % (q+1) == 0 ); - size_t n = tx.size() / (q+1); - size_t m = ty.size() / (q+1); - bool ok = r_(id_, q, n, m, tx, ty, px, py); - return ok; - } - /*! - Link from forward Jacobian sparsity sweep to old_atomic - - \copydetails atomic_base::for_sparse_jac - */ - virtual bool for_sparse_jac( - size_t q , - const vector< std::set >& r , - vector< std::set >& s ) - { size_t n = r.size(); - size_t m = s.size(); - bool ok = fjs_(id_, n, m, q, r, s); - return ok; - } - - /*! - Link from reverse Jacobian sparsity sweep to old_atomic. - - \copydetails atomic_base::rev_sparse_jac - */ - virtual bool rev_sparse_jac( - size_t q , - const vector< std::set >& rt , - vector< std::set >& st ) - { size_t n = st.size(); - size_t m = rt.size(); - bool ok = rjs_(id_, n, m, q, st, rt); - return ok; - } - /*! - Link from reverse Hessian sparsity sweep to old_atomic - - \copydetails atomic_base::rev_sparse_hes - */ - virtual bool rev_sparse_hes( - const vector& vx, - const vector& s , - vector& t , - size_t q , - const vector< std::set >& r , - const vector< std::set >& u , - vector< std::set >& v ) - { size_t m = u.size(); - size_t n = v.size(); - CPPAD_ASSERT_UNKNOWN( r.size() == n ); - CPPAD_ASSERT_UNKNOWN( s.size() == m ); - CPPAD_ASSERT_UNKNOWN( t.size() == n ); - // - // old interface used id instead of vx - bool ok = rhs_(id_, n, m, q, r, s, t, u, v); - return ok; - } -}; - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/omp_max_thread.hpp b/ct_core/include/ct/external/cppad/local/omp_max_thread.hpp deleted file mode 100644 index 49614b169..000000000 --- a/ct_core/include/ct/external/cppad/local/omp_max_thread.hpp +++ /dev/null @@ -1,95 +0,0 @@ -// $Id: omp_max_thread.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_OMP_MAX_THREAD_HPP -# define CPPAD_OMP_MAX_THREAD_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin omp_max_thread$$ -$spell - alloc - num - omp - OpenMp - CppAD -$$ - -$section OpenMP Parallel Setup$$ -$mindex omp_max_thread$$ - -$head Deprecated 2011-06-23$$ -Use $cref/thread_alloc::parallel_setup/ta_parallel_setup/$$ -to set the number of threads. - -$head Syntax$$ -$codei%AD<%Base%>::omp_max_thread(%number%) -%$$ - -$head Purpose$$ -By default, for each $codei%AD<%Base%>%$$ class there is only one -tape that records $cref/AD of Base/glossary/AD of Base/$$ operations. -This tape is a global variable and hence it cannot be used -by multiple OpenMP threads at the same time. -The $code omp_max_thread$$ function is used to set the -maximum number of OpenMP threads that can be active. -In this case, there is a different tape corresponding to each -$codei%AD<%Base%>%$$ class and thread pair. - -$head number$$ -The argument $icode number$$ has prototype -$codei% - size_t %number% -%$$ -It must be greater than zero and specifies the maximum number of -OpenMp threads that will be active at one time. - - -$head Independent$$ -Each call to $cref/Independent(x)/Independent/$$ -creates a new $cref/active/glossary/Tape/Active/$$ tape. -All of the operations with the corresponding variables -must be preformed by the same OpenMP thread. -This includes the corresponding call to -$cref/f.Dependent(x,y)/Dependent/$$ or the -$cref/ADFun f(x, y)/FunConstruct/Sequence Constructor/$$ -during which the tape stops recording and the variables -become parameters. - -$head Restriction$$ -No tapes can be -$cref/active/glossary/Tape/Active/$$ when this function is called. - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -void AD::omp_max_thread(size_t number) -{ -# ifdef _OPENMP - thread_alloc::parallel_setup( - number, omp_alloc::in_parallel, omp_alloc::get_thread_num - ); -# else - CPPAD_ASSERT_KNOWN( - number == 1, - "omp_max_thread: number > 1 and _OPENMP is not defined" - ); -# endif - parallel_ad(); -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/op.hpp b/ct_core/include/ct/external/cppad/local/op.hpp deleted file mode 100644 index 80236b5e9..000000000 --- a/ct_core/include/ct/external/cppad/local/op.hpp +++ /dev/null @@ -1,60 +0,0 @@ -// $Id: op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_OP_HPP -# define CPPAD_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// used by the sparse operators -# include - -// operations -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include - - -# endif diff --git a/ct_core/include/ct/external/cppad/local/op_code.hpp b/ct_core/include/ct/external/cppad/local/op_code.hpp deleted file mode 100644 index 07c0a390c..000000000 --- a/ct_core/include/ct/external/cppad/local/op_code.hpp +++ /dev/null @@ -1,1070 +0,0 @@ -// $Id: op_code.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_OP_CODE_HPP -# define CPPAD_OP_CODE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include -# include - -# include -# include - -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file op_code.hpp -Defines the OpCode enum type and functions related to it. - -*/ - - -/*! -Type used to distinguish different AD< \a Base > atomic operations. - -Each of the operators ends with the characters Op. Ignoring the Op at the end, -the operators appear in alphabetical order. Binary operation where both -operands have type AD< \a Base > use the following convention for thier endings: -\verbatim - Ending Left-Operand Right-Operand - pvOp parameter variable - vpOp variable parameter - vvOp variable variable -\endverbatim -For example, AddpvOp represents the addition operator where the left -operand is a parameter and the right operand is a variable. -*/ -// alphabetical order is checked by bin/check_op_code.sh -enum OpCode { - AbsOp, // abs(variable) - AcosOp, // acos(variable) - AcoshOp, // acosh(variable) - AddpvOp, // parameter + variable - AddvvOp, // variable + variable - AsinOp, // asin(variable) - AsinhOp, // asinh(variable) - AtanOp, // atan(variable) - AtanhOp, // atanh(variable) - BeginOp, // used to mark the beginning of the tape - CExpOp, // CondExpRel(left, right, trueCase, falseCase) - // arg[0] = the Rel operator: Lt, Le, Eq, Ge, Gt, or Ne - // arg[1] & 1 = is left a variable - // arg[1] & 2 = is right a variable - // arg[1] & 4 = is trueCase a variable - // arg[1] & 8 = is falseCase a variable - // arg[2] = index correspoding to left - // arg[3] = index correspoding to right - // arg[4] = index correspoding to trueCase - // arg[5] = index correspoding to falseCase - CosOp, // cos(variable) - CoshOp, // cosh(variable) - CSkipOp, // Conditional skip - // arg[0] = the Rel operator: Lt, Le, Eq, Ge, Gt, or Ne - // arg[1] & 1 = is left a variable - // arg[1] & 2 = is right a variable - // arg[2] = index correspoding to left - // arg[3] = index correspoding to right - // arg[4] = number of operations to skip if CExpOp comparision is true - // arg[5] = number of operations to skip if CExpOp comparision is false - // arg[6] -> arg[5+arg[4]] = skip operations if true - // arg[6+arg[4]] -> arg[5+arg[4]+arg[5]] = skip operations if false - // arg[6+arg[4]+arg[5]] = arg[4] + arg[5] - CSumOp, // Cummulative summation - // arg[0] = number of addition variables in summation - // arg[1] = number of subtraction variables in summation - // arg[2] = index of parameter that initializes summation - // arg[3] -> arg[2+arg[0]] = index for positive variables - // arg[3+arg[0]] -> arg[2+arg[0]+arg[1]] = index for minus variables - // arg[3+arg[0]+arg[1]] = arg[0] + arg[1] - DisOp, // discrete::eval(index, variable) - DivpvOp, // parameter / variable - DivvpOp, // variable / parameter - DivvvOp, // variable / variable - EndOp, // used to mark the end of the tape - EqpvOp, // parameter == variable - EqvvOp, // variable == variable - ErfOp, // erf(variable) - ExpOp, // exp(variable) - Expm1Op, // expm1(variable) - InvOp, // independent variable - LdpOp, // z[parameter] - LdvOp, // z[variable] - LepvOp, // parameter <= variable - LevpOp, // variable <= parameter - LevvOp, // variable <= variable - LogOp, // log(variable) - Log1pOp, // log1p(variable) - LtpvOp, // parameter < variable - LtvpOp, // variable < parameter - LtvvOp, // variable < variable - MulpvOp, // parameter * variable - MulvvOp, // variable * variable - NepvOp, // parameter != variable - NevvOp, // variable != variable - ParOp, // parameter - PowpvOp, // pow(parameter, variable) - PowvpOp, // pow(variable, parameter) - PowvvOp, // pow(variable, variable) - PriOp, // PrintFor(text, parameter or variable, parameter or variable) - SignOp, // sign(variable) - SinOp, // sin(variable) - SinhOp, // sinh(variable) - SqrtOp, // sqrt(variable) - StppOp, // z[parameter] = parameter - StpvOp, // z[parameter] = variable - StvpOp, // z[variable] = parameter - StvvOp, // z[variable] = variable - SubpvOp, // parameter - variable - SubvpOp, // variable - parameter - SubvvOp, // variable - variable - TanOp, // tan(variable) - TanhOp, // tan(variable) - // user atomic operation codes - UserOp, // start of a user atomic operaiton - // arg[0] = index of the operation if atomic_base class - // arg[1] = extra information passed trough by deprecated old atomic class - // arg[2] = number of arguments to this atomic function - // arg[3] = number of results for this atomic function - UsrapOp, // this user atomic argument is a parameter - UsravOp, // this user atomic argument is a variable - UsrrpOp, // this user atomic result is a parameter - UsrrvOp, // this user atomic result is a variable - ZmulpvOp, // azmul(parameter, variable) - ZmulvpOp, // azmul(variabe, parameter) - ZmulvvOp, // azmul(variable, variable) - NumberOp // number of operator codes (not an operator) -}; -// Note that bin/check_op_code.sh assumes the pattern '^\tNumberOp$' occurs -// at the end of this list and only at the end of this list. - -/*! -Number of arguments for a specified operator. - -\return -Number of arguments corresponding to the specified operator. - -\param op -Operator for which we are fetching the number of arugments. - -\par NumArgTable -this table specifes the number of arguments stored for each -occurance of the operator that is the i-th value in the OpCode enum type. -For example, for the first three OpCode enum values we have -\verbatim -OpCode j NumArgTable[j] Meaning -AbsOp 0 1 index of variable we are taking absolute value of -AcosOp 1 1 index of variable we are taking acos of -AcoshOp 2 1 index of variable we are taking acosh of -\endverbatim -Note that the meaning of the arguments depends on the operator. -*/ -inline size_t NumArg( OpCode op) -{ CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - - // agreement with OpCode is checked by bin/check_op_code.sh - static const size_t NumArgTable[] = { - 1, // AbsOp - 1, // AcosOp - 1, // AcoshOp - 2, // AddpvOp - 2, // AddvvOp - 1, // AsinOp - 1, // AsinhOp - 1, // AtanOp - 1, // AtanhOp - 1, // BeginOp offset first real argument to have index 1 - 6, // CExpOp - 1, // CosOp - 1, // CoshOp - 0, // CSkipOp (actually has a variable number of arguments, not zero) - 0, // CSumOp (actually has a variable number of arguments, not zero) - 2, // DisOp - 2, // DivpvOp - 2, // DivvpOp - 2, // DivvvOp - 0, // EndOp - 2, // EqpvOp - 2, // EqvvOp - 3, // ErfOp - 1, // ExpOp - 1, // Expm1Op - 0, // InvOp - 3, // LdpOp - 3, // LdvOp - 2, // LepvOp - 2, // LevpOp - 2, // LevvOp - 1, // LogOp - 1, // Log1pOp - 2, // LtpvOp - 2, // LtvpOp - 2, // LtvvOp - 2, // MulpvOp - 2, // MulvvOp - 2, // NepvOp - 2, // NevvOp - 1, // ParOp - 2, // PowpvOp - 2, // PowvpOp - 2, // PowvvOp - 5, // PriOp - 1, // SignOp - 1, // SinOp - 1, // SinhOp - 1, // SqrtOp - 3, // StppOp - 3, // StpvOp - 3, // StvpOp - 3, // StvvOp - 2, // SubpvOp - 2, // SubvpOp - 2, // SubvvOp - 1, // TanOp - 1, // TanhOp - 4, // UserOp - 1, // UsrapOp - 1, // UsravOp - 1, // UsrrpOp - 0, // UsrrvOp - 2, // ZmulpvOp - 2, // ZmulvpOp - 2, // ZmulvvOp - 0 // NumberOp not used - }; -# ifndef NDEBUG - // only do these checks once to save time - static bool first = true; - if( first ) - { CPPAD_ASSERT_UNKNOWN( size_t(NumberOp) + 1 == - sizeof(NumArgTable) / sizeof(NumArgTable[0]) - ); - CPPAD_ASSERT_UNKNOWN( size_t(NumberOp) <= - std::numeric_limits::max() - ); - first = false; - } - // do this check every time - CPPAD_ASSERT_UNKNOWN( size_t(op) < size_t(NumberOp) ); -# endif - - return NumArgTable[op]; -} - -/*! -Number of variables resulting from the specified operation. - -\param op -Operator for which we are fecching the number of results. - -\par NumResTable -table specifes the number of varibles that result for each -occurance of the operator that is the i-th value in the OpCode enum type. -For example, for the first three OpCode enum values we have -\verbatim -OpCode j NumResTable[j] Meaning -AbsOp 0 1 variable that is the result of the absolute value -AcosOp 1 2 acos(x) and sqrt(1-x*x) are required for this op -AcoshOp 2 2 acosh(x) and sqrt(x*x-1) are required for this op -\endverbatim -*/ -inline size_t NumRes(OpCode op) -{ CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - - // agreement with OpCode is checked by bin/check_op_code.sh - static const size_t NumResTable[] = { - 1, // AbsOp - 2, // AcosOp - 2, // AcoshOp - 1, // AddpvOp - 1, // AddvvOp - 2, // AsinOp - 2, // AsinhOp - 2, // AtanOp - 2, // AtanhOp - 1, // BeginOp offsets first variable to have index one (not zero) - 1, // CExpOp - 2, // CosOp - 2, // CoshOp - 0, // CSkipOp - 1, // CSumOp - 1, // DisOp - 1, // DivpvOp - 1, // DivvpOp - 1, // DivvvOp - 0, // EndOp - 0, // EqpvOp - 0, // EqvvOp - 5, // ErfOp - 1, // ExpOp - 1, // Expm1Op - 1, // InvOp - 1, // LdpOp - 1, // LdvOp - 0, // LepvOp - 0, // LevpOp - 0, // LevvOp - 1, // LogOp - 1, // Log1pOp - 0, // LtpvOp - 0, // LtvpOp - 0, // LtvvOp - 1, // MulpvOp - 1, // MulvvOp - 0, // NepvOp - 0, // NevvOp - 1, // ParOp - 3, // PowpvOp - 3, // PowvpOp - 3, // PowvvOp - 0, // PriOp - 1, // SignOp - 2, // SinOp - 2, // SinhOp - 1, // SqrtOp - 0, // StppOp - 0, // StpvOp - 0, // StvpOp - 0, // StvvOp - 1, // SubpvOp - 1, // SubvpOp - 1, // SubvvOp - 2, // TanOp - 2, // TanhOp - 0, // UserOp - 0, // UsrapOp - 0, // UsravOp - 0, // UsrrpOp - 1, // UsrrvOp - 1, // ZmulpvOp - 1, // ZmulvpOp - 1, // ZmulvvOp - 0 // NumberOp not used and avoids g++ 4.3.2 warn when pycppad builds - }; - // check ensuring conversion to size_t is as expected - CPPAD_ASSERT_UNKNOWN( size_t(NumberOp) + 1 == - sizeof(NumResTable) / sizeof(NumResTable[0]) - ); - // this test ensures that all indices are within the table - CPPAD_ASSERT_UNKNOWN( size_t(op) < size_t(NumberOp) ); - - return NumResTable[op]; -} - - -/*! -Fetch the name for a specified operation. - -\return -name of the specified operation. - -\param op -Operator for which we are fetching the name -*/ -inline const char* OpName(OpCode op) -{ // agreement with OpCode is checked by bin/check_op_code.sh - static const char *OpNameTable[] = { - "Abs" , - "Acos" , - "Acosh" , - "Addpv" , - "Addvv" , - "Asin" , - "Asinh" , - "Atan" , - "Atanh" , - "Begin" , - "CExp" , - "Cos" , - "Cosh" , - "CSkip" , - "CSum" , - "Dis" , - "Divpv" , - "Divvp" , - "Divvv" , - "End" , - "Eqpv" , - "Eqvv" , - "Erf" , - "Exp" , - "Expm1" , - "Inv" , - "Ldp" , - "Ldv" , - "Lepv" , - "Levp" , - "Levv" , - "Log" , - "Log1p" , - "Ltpv" , - "Ltvp" , - "Ltvv" , - "Mulpv" , - "Mulvv" , - "Nepv" , - "Nevv" , - "Par" , - "Powpv" , - "Powvp" , - "Powvv" , - "Pri" , - "Sign" , - "Sin" , - "Sinh" , - "Sqrt" , - "Stpp" , - "Stpv" , - "Stvp" , - "Stvv" , - "Subpv" , - "Subvp" , - "Subvv" , - "Tan" , - "Tanh" , - "User" , - "Usrap" , - "Usrav" , - "Usrrp" , - "Usrrv" , - "Zmulpv", - "Zmulvp", - "Zmulvv", - "Number" // not used - }; - // check ensuring conversion to size_t is as expected - CPPAD_ASSERT_UNKNOWN( - size_t(NumberOp) + 1 == sizeof(OpNameTable)/sizeof(OpNameTable[0]) - ); - // this test ensures that all indices are within the table - CPPAD_ASSERT_UNKNOWN( size_t(op) < size_t(NumberOp) ); - - return OpNameTable[op]; -} - -/*! -Prints a single field corresponding to an operator. - -A specified leader is printed in front of the value -and then the value is left justified in the following width character. - -\tparam Type -is the type of the value we are printing. - -\param os -is the stream that we are printing to. - -\param leader -are characters printed before the value. - -\param value -is the value being printed. - -\param width -is the number of character to print the value in. -If the value does not fit in the width, the value is replace -by width '*' characters. -*/ -template -void printOpField( - std::ostream &os , - const char * leader , - const Type &value , - size_t width ) -{ - std::ostringstream buffer; - std::string str; - - // first print the leader - os << leader; - - // print the value into an internal buffer - buffer << std::setw(width) << value; - str = buffer.str(); - - // length of the string - size_t len = str.size(); - if( len > width ) - { size_t i; - for(i = 0; i < width-1; i++) - os << str[i]; - os << "*"; - return; - } - - // count number of spaces at begining - size_t nspace = 0; - while(str[nspace] == ' ' && nspace < len) - nspace++; - - // left justify the string - size_t i = nspace; - while( i < len ) - os << str[i++]; - - i = width - len + nspace; - while(i--) - os << " "; -} - -/*! -Prints a single operator and its operands - -\tparam Base -Is the base type for these AD< \a Base > operations. - -\param os -is the output stream that the information is printed on. - -\param play -Is the entire recording for the tape that this operator is in. - -\param i_op -is the index for the operator corresponding to this operation. - -\param i_var -is the index for the variable corresponding to the result of this operation -(if NumRes(op) > 0). - -\param op -The operator code (OpCode) for this operation. - -\param ind -is the vector of argument indices for this operation -(must have NumArg(op) elements). -*/ -template -void printOp( - std::ostream& os , - const player* play , - size_t i_op , - size_t i_var , - OpCode op , - const addr_t* ind ) -{ size_t i; - CPPAD_ASSERT_KNOWN( - ! thread_alloc::in_parallel() , - "cannot print trace of AD operations in parallel mode" - ); - static const char *CompareOpName[] = - { "Lt", "Le", "Eq", "Ge", "Gt", "Ne" }; - - // print operator - printOpField(os, "o=", i_op, 5); - if( NumRes(op) > 0 && op != BeginOp ) - printOpField(os, "v=", i_var, 5); - else printOpField(os, "v=", "", 5); - if( op == CExpOp || op == CSkipOp ) - { printOpField(os, "", OpName(op), 5); - printOpField(os, "", CompareOpName[ ind[0] ], 3); - } - else printOpField(os, "", OpName(op), 8); - - // print other fields - size_t ncol = 5; - switch( op ) - { - case CSkipOp: - /* - ind[0] = the Rel operator: Lt, Le, Eq, Ge, Gt, or Ne - ind[1] & 1 = is left a variable - ind[1] & 2 = is right a variable - ind[2] = index correspoding to left - ind[3] = index correspoding to right - ind[4] = number of operations to skip if CExpOp comparision is true - ind[5] = number of operations to skip if CExpOp comparision is false - ind[6] -> ind[5+ind[4]] = skip operations if true - ind[6+ind[4]] -> ind[5+ind[4]+ind[5]] = skip operations if false - ind[6+ind[4]+ind[5]] = ind[4] + ind[5] - */ - CPPAD_ASSERT_UNKNOWN( ind[6+ind[4]+ind[5]] == ind[4]+ind[5] ); - CPPAD_ASSERT_UNKNOWN(ind[1] != 0); - if( ind[1] & 1 ) - printOpField(os, " vl=", ind[2], ncol); - else printOpField(os, " pl=", play->GetPar(ind[2]), ncol); - if( ind[1] & 2 ) - printOpField(os, " vr=", ind[3], ncol); - else printOpField(os, " pr=", play->GetPar(ind[3]), ncol); - if( size_t(ind[4]) < 3 ) - { for(i = 0; i < size_t(ind[4]); i++) - printOpField(os, " ot=", ind[6+i], ncol); - } - else - { printOpField(os, "\n\tot=", ind[6+0], ncol); - for(i = 1; i < size_t(ind[4]); i++) - printOpField(os, " ot=", ind[6+i], ncol); - } - if( size_t(ind[5]) < 3 ) - { for(i = 0; i < size_t(ind[5]); i++) - printOpField(os, " of=", ind[6+ind[4]+i], ncol); - } - else - { printOpField(os, "\n\tof=", ind[6+ind[4]+0], ncol); - { for(i = 1; i < size_t(ind[5]); i++) - printOpField(os, " of=", ind[6+ind[4]+i], ncol); - } - } - break; - - case CSumOp: - /* - ind[0] = number of addition variables in summation - ind[1] = number of subtraction variables in summation - ind[2] = index of parameter that initializes summation - ind[3], ... , ind[2+ind[0]] = index for positive variables - ind[3+ind[0]], ..., ind[2+ind[0]+ind[1]] = negative variables - ind[3+ind[0]+ind[1]] == ind[0] + ind[1] - */ - CPPAD_ASSERT_UNKNOWN( ind[3+ind[0]+ind[1]] == ind[0]+ind[1] ); - printOpField(os, " pr=", play->GetPar(ind[2]), ncol); - for(i = 0; i < size_t(ind[0]); i++) - printOpField(os, " +v=", ind[3+i], ncol); - for(i = 0; i < size_t(ind[1]); i++) - printOpField(os, " -v=", ind[3+ind[0]+i], ncol); - break; - - case LdpOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 3 ); - printOpField(os, "off=", ind[0], ncol); - printOpField(os, "idx=", ind[1], ncol); - break; - - case LdvOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 3 ); - printOpField(os, "off=", ind[0], ncol); - printOpField(os, " v=", ind[1], ncol); - break; - - case StppOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 3 ); - printOpField(os, "off=", ind[0], ncol); - printOpField(os, "idx=", ind[1], ncol); - printOpField(os, " pr=", play->GetPar(ind[2]), ncol); - break; - - case StpvOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 3 ); - printOpField(os, "off=", ind[0], ncol); - printOpField(os, "idx=", ind[1], ncol); - printOpField(os, " vr=", ind[2], ncol); - break; - - case StvpOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 3 ); - printOpField(os, "off=", ind[0], ncol); - printOpField(os, " vl=", ind[1], ncol); - printOpField(os, " pr=", play->GetPar(ind[2]), ncol); - break; - - case StvvOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 3 ); - printOpField(os, "off=", ind[0], ncol); - printOpField(os, " vl=", ind[1], ncol); - printOpField(os, " vr=", ind[2], ncol); - break; - - case AddvvOp: - case DivvvOp: - case EqvvOp: - case LevvOp: - case LtvvOp: - case NevvOp: - case MulvvOp: - case PowvvOp: - case SubvvOp: - case ZmulvvOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 2 ); - printOpField(os, " vl=", ind[0], ncol); - printOpField(os, " vr=", ind[1], ncol); - break; - - case AddpvOp: - case EqpvOp: - case DivpvOp: - case LepvOp: - case LtpvOp: - case NepvOp: - case SubpvOp: - case MulpvOp: - case PowpvOp: - case ZmulpvOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 2 ); - printOpField(os, " pl=", play->GetPar(ind[0]), ncol); - printOpField(os, " vr=", ind[1], ncol); - break; - - case DivvpOp: - case LevpOp: - case LtvpOp: - case PowvpOp: - case SubvpOp: - case ZmulvpOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 2 ); - printOpField(os, " vl=", ind[0], ncol); - printOpField(os, " pr=", play->GetPar(ind[1]), ncol); - break; - - case AbsOp: - case AcosOp: - case AcoshOp: - case AsinOp: - case AsinhOp: - case AtanOp: - case AtanhOp: - case CosOp: - case CoshOp: - case ExpOp: - case Expm1Op: - case LogOp: - case Log1pOp: - case SignOp: - case SinOp: - case SinhOp: - case SqrtOp: - case UsravOp: - case TanOp: - case TanhOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ); - printOpField(os, " v=", ind[0], ncol); - break; - - case ErfOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 3 ); - // ind[1] points to the parameter 0 - // ind[2] points to the parameter 2 / sqrt(pi) - printOpField(os, " v=", ind[0], ncol); - break; - - case ParOp: - case UsrapOp: - case UsrrpOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ); - printOpField(os, " p=", play->GetPar(ind[0]), ncol); - break; - - case UserOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 4 ); - { std::string name = atomic_base::class_name(ind[0]); - printOpField(os, " f=", name.c_str(), ncol); - printOpField(os, " i=", ind[1], ncol); - printOpField(os, " n=", ind[2], ncol); - printOpField(os, " m=", ind[3], ncol); - } - break; - - case PriOp: - CPPAD_ASSERT_NARG_NRES(op, 5, 0); - if( ind[0] & 1 ) - printOpField(os, " v=", ind[1], ncol); - else printOpField(os, " p=", play->GetPar(ind[1]), ncol); - os << "before=\"" << play->GetTxt(ind[2]) << "\""; - if( ind[0] & 2 ) - printOpField(os, " v=", ind[3], ncol); - else printOpField(os, " p=", play->GetPar(ind[3]), ncol); - os << "after=\"" << play->GetTxt(ind[4]) << "\""; - break; - - case BeginOp: - // argument not used (created by independent) - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ); - break; - - case EndOp: - case InvOp: - case UsrrvOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 0 ); - break; - - case DisOp: - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 2 ); - { const char* name = discrete::name(ind[0]); - printOpField(os, " f=", name, ncol); - printOpField(os, " x=", ind[1], ncol); - } - break; - - - case CExpOp: - CPPAD_ASSERT_UNKNOWN(ind[1] != 0); - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 6 ); - if( ind[1] & 1 ) - printOpField(os, " vl=", ind[2], ncol); - else printOpField(os, " pl=", play->GetPar(ind[2]), ncol); - if( ind[1] & 2 ) - printOpField(os, " vr=", ind[3], ncol); - else printOpField(os, " pr=", play->GetPar(ind[3]), ncol); - if( ind[1] & 4 ) - printOpField(os, " vt=", ind[4], ncol); - else printOpField(os, " pt=", play->GetPar(ind[4]), ncol); - if( ind[1] & 8 ) - printOpField(os, " vf=", ind[5], ncol); - else printOpField(os, " pf=", play->GetPar(ind[5]), ncol); - break; - - default: - CPPAD_ASSERT_UNKNOWN(0); - } -} - -/*! -Prints the result values correspnding to an operator. - -\tparam Base -Is the base type for these AD< \a Base > operations. - -\tparam Value -Determines the type of the values that we are printing. - -\param os -is the output stream that the information is printed on. - -\param nfz -is the number of forward sweep calculated values of type Value -that correspond to this operation -(ignored if NumRes(op) == 0). - -\param fz -points to the first forward calculated value -that correspond to this operation -(ignored if NumRes(op) == 0). - -\param nrz -is the number of reverse sweep calculated values of type Value -that correspond to this operation -(ignored if NumRes(op) == 0). - -\param rz -points to the first reverse calculated value -that correspond to this operation -(ignored if NumRes(op) == 0). -*/ -template -void printOpResult( - std::ostream &os , - size_t nfz , - const Value *fz , - size_t nrz , - const Value *rz ) -{ - size_t k; - for(k = 0; k < nfz; k++) - os << "| fz[" << k << "]=" << fz[k]; - for(k = 0; k < nrz; k++) - os << "| rz[" << k << "]=" << rz[k]; -} - -/*! -If NDEBUG is not defined, assert that arguments come before result. - -\param op -Operator for which we are checking order. -All the operators are checked except for those of the form UserOp or Usr..Op. - -\param result -is the variable index for the result. - -\param arg -is a vector of lenght NumArg(op) pointing to the arguments -for this operation. -*/ -inline void assert_arg_before_result( - OpCode op, const addr_t* arg, size_t result -) -{ - switch( op ) - { - - // These cases are not included below - case UserOp: - case UsrapOp: - case UsravOp: - case UsrrpOp: - case UsrrvOp: - break; - // ------------------------------------------------------------------ - - // 0 arguments - case CSkipOp: - case CSumOp: - case EndOp: - case InvOp: - break; - // ------------------------------------------------------------------ - - // 1 argument, but is not used - case BeginOp: - break; - - // 1 argument , 1 result - case AbsOp: - case ExpOp: - case Expm1Op: - case LogOp: - case Log1pOp: - case ParOp: - case SignOp: - case SqrtOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < result ); - break; - - // 1 argument, 2 results - case AcosOp: - case AcoshOp: - case AsinOp: - case AsinhOp: - case AtanOp: - case AtanhOp: - case CosOp: - case CoshOp: - case SinOp: - case SinhOp: - case TanOp: - case TanhOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) + 1 < result ); - break; - - // 1 argument, 5 results - case ErfOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) + 4 < result ); - break; - // ------------------------------------------------------------------ - // 2 arguments, no results - case LepvOp: - case LtpvOp: - case EqpvOp: - case NepvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) <= result ); - break; - // - case LevpOp: - case LtvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) <= result ); - break; - // - case LevvOp: - case LtvvOp: - case EqvvOp: - case NevvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) <= result ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) <= result ); - break; - - // 2 arguments (both variables), 1 results - case AddvvOp: - case DivvvOp: - case MulvvOp: - case SubvvOp: - case ZmulvvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < result ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < result ); - break; - - // 2 arguments (first variables), 1 results - case DivvpOp: - case SubvpOp: - case ZmulvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < result ); - break; - - // 2 arguments (second variables), 1 results - case AddpvOp: - case DisOp: - case DivpvOp: - case MulpvOp: - case SubpvOp: - case ZmulpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < result ); - break; - - // 2 arguments (both variables), 3 results - case PowvvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) + 2 < result ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) + 2 < result ); - break; - - // 2 arguments (first variable), 3 results - case PowvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) + 2 < result ); - break; - - // 2 arguments (second variable), 3 results - case PowpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) + 2 < result ); - break; - // ------------------------------------------------------------------ - - // 3 arguments, none variables - case LdpOp: - case StppOp: - break; - - // 3 arguments, second variable, 1 result - case LdvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < result ); - break; - - // 3 arguments, third variable, no result - case StpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) <= result ); - break; - - // 3 arguments, second variable, no result - case StvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) <= result ); - break; - - // 3 arguments, second and third variable, no result - case StvvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) <= result ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) <= result ); - break; - // ------------------------------------------------------------------ - - // 5 arguments, no result - case PriOp: - if( arg[0] & 1 ) - { CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) <= result ); - } - if( arg[0] & 2 ) - { CPPAD_ASSERT_UNKNOWN( size_t(arg[3]) <= result ); - } - break; - // ------------------------------------------------------------------ - - // 6 arguments, 1 result - case CExpOp: - if( arg[1] & 1 ) - { CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < result ); - } - if( arg[1] & 2 ) - { CPPAD_ASSERT_UNKNOWN( size_t(arg[3]) < result ); - } - if( arg[1] & 4 ) - { CPPAD_ASSERT_UNKNOWN( size_t(arg[4]) < result ); - } - if( arg[1] & 8 ) - { CPPAD_ASSERT_UNKNOWN( size_t(arg[5]) < result ); - } - break; - // ------------------------------------------------------------------ - - default: - CPPAD_ASSERT_UNKNOWN(false); - break; - - } - return; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/opt_val_hes.hpp b/ct_core/include/ct/external/cppad/local/opt_val_hes.hpp deleted file mode 100644 index 6411febf3..000000000 --- a/ct_core/include/ct/external/cppad/local/opt_val_hes.hpp +++ /dev/null @@ -1,525 +0,0 @@ -// $Id: opt_val_hes.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_OPT_VAL_HES_HPP -# define CPPAD_OPT_VAL_HES_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin opt_val_hes$$ -$spell - hes - sy - Jacobian - hes - signdet - jac - Bradley - const - CppAD -$$ - - - -$section Jacobian and Hessian of Optimal Values$$ -$mindex opt_val_hes$$ - -$head Syntax$$ -$icode%signdet% = opt_val_hes(%x%, %y%, %fun%, %jac%, %hes%)%$$ - -$head See Also$$ -$cref BenderQuad$$ - -$head Reference$$ -Algorithmic differentiation of implicit functions and optimal values, -Bradley M. Bell and James V. Burke, Advances in Automatic Differentiation, -2008, Springer. - -$head Purpose$$ -We are given a function -$latex S : \B{R}^n \times \B{R}^m \rightarrow \B{R}^\ell$$ -and we define $latex F : \B{R}^n \times \B{R}^m \rightarrow \B{R}$$ -and $latex V : \B{R}^n \rightarrow \B{R} $$ by -$latex \[ -\begin{array}{rcl} - F(x, y) & = & \sum_{k=0}^{\ell-1} S_k ( x , y) - \\ - V(x) & = & F [ x , Y(x) ] - \\ - 0 & = & \partial_y F [x , Y(x) ] -\end{array} -\] $$ -We wish to compute the Jacobian -and possibly also the Hessian, of $latex V (x)$$. - -$head BaseVector$$ -The type $icode BaseVector$$ must be a -$cref SimpleVector$$ class. -We use $icode Base$$ to refer to the type of the elements of -$icode BaseVector$$; i.e., -$codei% - %BaseVector%::value_type -%$$ - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %BaseVector%& %x% -%$$ -and its size must be equal to $icode n$$. -It specifies the point at which we evaluating -the Jacobian $latex V^{(1)} (x)$$ -(and possibly the Hessian $latex V^{(2)} (x)$$). - - -$head y$$ -The argument $icode y$$ has prototype -$codei% - const %BaseVector%& %y% -%$$ -and its size must be equal to $icode m$$. -It must be equal to $latex Y(x)$$; i.e., -it must solve the implicit equation -$latex \[ - 0 = \partial_y F ( x , y) -\] $$ - -$head Fun$$ -The argument $icode fun$$ is an object of type $icode Fun$$ -which must support the member functions listed below. -CppAD will may be recording operations of the type $codei%AD<%Base%>%$$ -when these member functions are called. -These member functions must not stop such a recording; e.g., -they must not call $cref/AD::abort_recording/abort_recording/$$. - -$subhead Fun::ad_vector$$ -The type $icode%Fun%::ad_vector%$$ must be a -$cref SimpleVector$$ class with elements of type $codei%AD<%Base%>%$$; i.e. -$codei% - %Fun%::ad_vector::value_type -%$$ -is equal to $codei%AD<%Base%>%$$. - -$subhead fun.ell$$ -The type $icode Fun$$ must support the syntax -$codei% - %ell% = %fun%.ell() -%$$ -where $icode ell$$ has prototype -$codei% - size_t %ell% -%$$ -and is the value of $latex \ell$$; i.e., -the number of terms in the summation. -$pre - -$$ -One can choose $icode ell$$ equal to one, and have -$latex S(x,y)$$ the same as $latex F(x, y)$$. -Each of the functions $latex S_k (x , y)$$, -(in the summation defining $latex F(x, y)$$) -is differentiated separately using AD. -For very large problems, breaking $latex F(x, y)$$ into the sum -of separate simpler functions may reduce the amount of memory necessary for -algorithmic differentiation and there by speed up the process. - -$subhead fun.s$$ -The type $icode Fun$$ must support the syntax -$codei% - %s_k% = %fun%.s(%k%, %x%, %y%) -%$$ -The $icode%fun%.s%$$ argument $icode k$$ has prototype -$codei% - size_t %k% -%$$ -and is between zero and $icode%ell% - 1%$$. -The argument $icode x$$ to $icode%fun%.s%$$ has prototype -$codei% - const %Fun%::ad_vector& %x% -%$$ -and its size must be equal to $icode n$$. -The argument $icode y$$ to $icode%fun%.s%$$ has prototype -$codei% - const %Fun%::ad_vector& %y% -%$$ -and its size must be equal to $icode m$$. -The $icode%fun%.s%$$ result $icode s_k$$ has prototype -$codei% - AD<%Base%> %s_k% -%$$ -and its value must be given by $latex s_k = S_k ( x , y )$$. - -$subhead fun.sy$$ -The type $icode Fun$$ must support the syntax -$codei% - %sy_k% = %fun%.sy(%k%, %x%, %y%) -%$$ -The argument $icode k$$ to $icode%fun%.sy%$$ has prototype -$codei% - size_t %k% -%$$ -The argument $icode x$$ to $icode%fun%.sy%$$ has prototype -$codei% - const %Fun%::ad_vector& %x% -%$$ -and its size must be equal to $icode n$$. -The argument $icode y$$ to $icode%fun%.sy%$$ has prototype -$codei% - const %Fun%::ad_vector& %y% -%$$ -and its size must be equal to $icode m$$. -The $icode%fun%.sy%$$ result $icode sy_k$$ has prototype -$codei% - %Fun%::ad_vector %sy_k% -%$$ -its size must be equal to $icode m$$, -and its value must be given by $latex sy_k = \partial_y S_k ( x , y )$$. - -$head jac$$ -The argument $icode jac$$ has prototype -$codei% - %BaseVector%& %jac% -%$$ -and has size $icode n$$ or zero. -The input values of its elements do not matter. -If it has size zero, it is not affected. Otherwise, on output -it contains the Jacobian of $latex V (x)$$; i.e., -for $latex j = 0 , \ldots , n-1$$, -$latex \[ - jac[ j ] = V^{(1)} (x)_j -\] $$ -where $icode x$$ is the first argument to $code opt_val_hes$$. - -$head hes$$ -The argument $icode hes$$ has prototype -$codei% - %BaseVector%& %hes% -%$$ -and has size $icode%n% * %n%$$ or zero. -The input values of its elements do not matter. -If it has size zero, it is not affected. Otherwise, on output -it contains the Hessian of $latex V (x)$$; i.e., -for $latex i = 0 , \ldots , n-1$$, and -$latex j = 0 , \ldots , n-1$$, -$latex \[ - hes[ i * n + j ] = V^{(2)} (x)_{i,j} -\] $$ - - -$head signdet$$ -If $icode%hes%$$ has size zero, $icode signdet$$ is not defined. -Otherwise -the return value $icode signdet$$ is the sign of the determinant for -$latex \partial_{yy}^2 F(x , y) $$. -If it is zero, then the matrix is singular and -the Hessian is not computed ($icode hes$$ is not changed). - -$head Example$$ -$children% - example/opt_val_hes.cpp -%$$ -The file -$cref opt_val_hes.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file opt_val_hes.hpp -\brief Computing Jabobians and Hessians of Optimal Values -*/ - -/*! -Computing Jabobians and Hessians of Optimal Values - -We are given a function -\f$ S : {\rm R}^n \times {\rm R}^m \rightarrow {\rm R}^\ell \f$ -and we define \f$ F : {\rm R}^n \times {\rm R}^m \rightarrow {\rm R} \f$ -and \f$ V : {\rm R}^n \rightarrow {\rm R} \f$ by -\f[ -\begin{array}{rcl} - F(x, y) & = & \sum_{k=0}^{\ell-1} S_k ( x , y) - \\ - V(x) & = & F [ x , Y(x) ] - \\ - 0 & = & \partial_y F [x , Y(x) ] -\end{array} -\f] -We wish to compute the Jacobian -and possibly also the Hessian, of \f$ V (x) \f$. - -\tparam BaseVector -The type \c BaseVector must be a SimpleVector class. -We use \c Base to refer to the type of the elements of -\c BaseVector; i.e., -BaseVector::value_type. - -\param x -is a vector with size \c n. -It specifies the point at which we evaluating -the Jacobian \f$ V^{(1)} (x) \f$ -(and possibly the Hessian \f$ V^{(2)} (x) \f$). - - -\param y -is a vector with size \c m. -It must be equal to \f$ Y(x) \f$; i.e., -it must solve the implicit equation -\f[ - 0 = \partial_y F ( x , y) -\f] - -\param fun -The argument \c fun is an object of type \c Fun -wich must support the member functions listed below. -CppAD will may be recording operations of the type \c AD -when these member functions are called. -These member functions must not stop such a recording; e.g., -they must not call \c AD::abort_recording. - -\par Fun::ad_vector -The type Fun::ad_vector must be a -SimpleVector class with elements of type \c AD; i.e. -Fun::ad_vector::value_type -is equal to \c AD. - -\par fun.ell -the type \c Fun must support the syntax -\verbatim - ell = fun.ell() -\endverbatim -where \c ell is a \c size_t value that is set to \f$ \ell \f$; i.e., -the number of terms in the summation. - -\par fun.s -The type \c Fun must support the syntax -\verbatim - s_k = fun.s(k, x, y) -\endverbatim -The argument \c k has prototype size_t k. -The argument \c x has prototype const Fun::ad_vector& x -and its size must be equal to \c n. -The argument \c y has prototype const Fun::ad_vector& y -and its size must be equal to \c m. -The return value \c s_k has prototype \c AD s_k -and its value must be given by \f$ s_k = S_k ( x , y ) \f$. - -\par fun.sy -The type \c Fun must support the syntax -\verbatim - sy_k = fun.sy(k, x, y) -\endverbatim -The argument \c k has prototype size_t k. -The argument \c x has prototype const Fun::ad_vector& x -and its size must be equal to \c n. -The argument \c y has prototype const Fun::ad_vector& y -and its size must be equal to \c m. -The return value \c sy_k has prototype Fun::ad_vector& sy_k, -its size is \c m -and its value must be given by \f$ sy_k = \partial_y S_k ( x , y ) \f$. - -\param jac -is a vector with size \c n or zero. -The input values of its elements do not matter. -If it has size zero, it is not affected. Otherwise, on output -it contains the Jacobian of \f$ V (x) \f$; i.e., -for \f$ j = 0 , \ldots , n-1 \f$, -\f[ - jac[ j ] = V^{(1)} (x)_j -\f] $$ -where \c x is the first argument to \c opt_val_hes. - -\param hes -is a vector with size n * n or zero. -The input values of its elements do not matter. -If it has size zero, it is not affected. Otherwise, on output -it contains the Hessian of \f$ V (x) \f$; i.e., -for \f$ i = 0 , \ldots , n-1 \f$, and -\f$ j = 0 , \ldots , n-1 \f$, -\f[ - hes[ i * n + j ] = V^{(2)} (x)_{i,j} -\f] - -\return -If hes.size() == 0, the return value is not defined. -Otherwise, -the return value is the sign of the determinant for -\f$ \partial_{yy}^2 F(x , y) \f$$. -If it is zero, then the matrix is singular and \c hes is not set -to its specified value. -*/ - - -template -int opt_val_hes( - const BaseVector& x , - const BaseVector& y , - Fun fun , - BaseVector& jac , - BaseVector& hes ) -{ // determine the base type - typedef typename BaseVector::value_type Base; - - // check that BaseVector is a SimpleVector class with Base elements - CheckSimpleVector(); - - // determine the AD vector type - typedef typename Fun::ad_vector ad_vector; - - // check that ad_vector is a SimpleVector class with AD elements - CheckSimpleVector< AD , ad_vector >(); - - // size of the x and y spaces - size_t n = size_t(x.size()); - size_t m = size_t(y.size()); - - // number of terms in the summation - size_t ell = fun.ell(); - - // check size of return values - CPPAD_ASSERT_KNOWN( - size_t(jac.size()) == n || jac.size() == 0, - "opt_val_hes: size of the vector jac is not equal to n or zero" - ); - CPPAD_ASSERT_KNOWN( - size_t(hes.size()) == n * n || hes.size() == 0, - "opt_val_hes: size of the vector hes is not equal to n * n or zero" - ); - - // some temporary indices - size_t i, j, k; - - // AD version of S_k(x, y) - ad_vector s_k(1); - - // ADFun version of S_k(x, y) - ADFun S_k; - - // AD version of x - ad_vector a_x(n); - - // AD version of y - ad_vector a_y(n); - - if( jac.size() > 0 ) - { // this is the easy part, computing the V^{(1)} (x) which is equal - // to \partial_x F (x, y) (see Thoerem 2 of the reference). - - // copy x and y to AD version - for(j = 0; j < n; j++) - a_x[j] = x[j]; - for(j = 0; j < m; j++) - a_y[j] = y[j]; - - // initialize summation - for(j = 0; j < n; j++) - jac[j] = Base(0.); - - // add in \partial_x S_k (x, y) - for(k = 0; k < ell; k++) - { // start recording - Independent(a_x); - // record - s_k[0] = fun.s(k, a_x, a_y); - // stop recording and store in S_k - S_k.Dependent(a_x, s_k); - // compute partial of S_k with respect to x - BaseVector jac_k = S_k.Jacobian(x); - // add \partial_x S_k (x, y) to jac - for(j = 0; j < n; j++) - jac[j] += jac_k[j]; - } - } - // check if we are done - if( hes.size() == 0 ) - return 0; - - /* - In this case, we need to compute the Hessian. Using Theorem 1 of the - reference: - Y^{(1)}(x) = - F_yy (x, y)^{-1} F_yx (x, y) - Using Theorem 2 of the reference: - V^{(2)}(x) = F_xx (x, y) + F_xy (x, y) Y^{(1)}(x) - */ - // Base and AD version of xy - BaseVector xy(n + m); - ad_vector a_xy(n + m); - for(j = 0; j < n; j++) - a_xy[j] = xy[j] = x[j]; - for(j = 0; j < m; j++) - a_xy[n+j] = xy[n+j] = y[j]; - - // Initialization summation for Hessian of F - size_t nm_sq = (n + m) * (n + m); - BaseVector F_hes(nm_sq); - for(j = 0; j < nm_sq; j++) - F_hes[j] = Base(0.); - BaseVector hes_k(nm_sq); - - // add in Hessian of S_k to hes - for(k = 0; k < ell; k++) - { // start recording - Independent(a_xy); - // split out x - for(j = 0; j < n; j++) - a_x[j] = a_xy[j]; - // split out y - for(j = 0; j < m; j++) - a_y[j] = a_xy[n+j]; - // record - s_k[0] = fun.s(k, a_x, a_y); - // stop recording and store in S_k - S_k.Dependent(a_xy, s_k); - // when computing the Hessian it pays to optimize the tape - S_k.optimize(); - // compute Hessian of S_k - hes_k = S_k.Hessian(xy, 0); - // add \partial_x S_k (x, y) to jac - for(j = 0; j < nm_sq; j++) - F_hes[j] += hes_k[j]; - } - // Extract F_yx - BaseVector F_yx(m * n); - for(i = 0; i < m; i++) - { for(j = 0; j < n; j++) - F_yx[i * n + j] = F_hes[ (i+n)*(n+m) + j ]; - } - // Extract F_yy - BaseVector F_yy(n * m); - for(i = 0; i < m; i++) - { for(j = 0; j < m; j++) - F_yy[i * m + j] = F_hes[ (i+n)*(n+m) + j + n ]; - } - - // compute - Y^{(1)}(x) = F_yy (x, y)^{-1} F_yx (x, y) - BaseVector neg_Y_x(m * n); - Base logdet; - int signdet = CppAD::LuSolve(m, n, F_yy, F_yx, neg_Y_x, logdet); - if( signdet == 0 ) - return signdet; - - // compute hes = F_xx (x, y) + F_xy (x, y) Y^{(1)}(x) - for(i = 0; i < n; i++) - { for(j = 0; j < n; j++) - { hes[i * n + j] = F_hes[ i*(n+m) + j ]; - for(k = 0; k < m; k++) - hes[i*n+j] -= F_hes[i*(n+m) + k+n] * neg_Y_x[k*n+j]; - } - } - return signdet; -} - -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize.hpp b/ct_core/include/ct/external/cppad/local/optimize.hpp deleted file mode 100644 index 676ff249d..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize.hpp +++ /dev/null @@ -1,3069 +0,0 @@ -// $Id: optimize.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_OPTIMIZE_HPP -# define CPPAD_OPTIMIZE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin optimize$$ -$spell - enum - jac - bool - Taylor - var - CppAD - cppad - std - CondExpEq -$$ - -$section Optimize an ADFun Object Tape$$ -$mindex sequence operations speed memory NDEBUG$$ - - -$head Syntax$$ -$icode%f%.optimize()%$$ - - -$head Purpose$$ -The operation sequence corresponding to an $cref ADFun$$ object can -be very large and involve many operations; see the -size functions in $cref seq_property$$. -The $icode%f%.optimize%$$ procedure reduces the number of operations, -and thereby the time and the memory, required to -compute function and derivative values. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ - -$head Improvements$$ -You can see the reduction in number of variables in the operation sequence -by calling the function $cref/f.size_var()/seq_property/size_var/$$ -before and after the optimization procedure. -Given that the optimization procedure takes time, -it may be faster to skip this optimize procedure and just compute -derivatives using the original operation sequence. - -$subhead Testing$$ -You can run the CppAD $cref/speed/speed_main/$$ tests and see -the corresponding changes in number of variables and execution time; -see $cref cmake_check$$. - -$head Efficiency$$ -The $code optimize$$ member function -may greatly reduce the number of variables -in the operation sequence; see $cref/size_var/seq_property/size_var/$$. -If a $cref/zero order forward/forward_zero/$$ calculation is done during -the construction of $icode f$$, it will require more memory -and time than required after the optimization procedure. -In addition, it will need to be redone. -For this reason, it is more efficient to use -$codei% - ADFun<%Base%> %f%; - %f%.Dependent(%x%, %y%); - %f%.optimize(); -%$$ -instead of -$codei% - ADFun<%Base%> %f%(%x%, %y%) - %f%.optimize(); -%$$ -See the discussion about -$cref/sequence constructors/FunConstruct/Sequence Constructor/$$. - -$head Atomic Functions$$ -There are some subtitle issue with optimized $cref atomic$$ functions -$latex v = g(u)$$: - -$subhead rev_sparse_jac$$ -The $cref atomic_rev_sparse_jac$$ function is be used to determine -which components of $icode u$$ affect the dependent variables of $icode f$$. -For each atomic operation, the current -$cref/atomic_sparsity/atomic_option/atomic_sparsity/$$ setting is used -to determine if $code pack_sparsity_enum$$, $code bool_sparsity_enum$$, -or $code set_sparsity_enum$$ is used to determine dependency relations -between argument and result variables. - -$subhead nan$$ -If $icode%u%[%i%]%$$ does not affect the value of -the dependent variables for $icode f$$, -the value of $icode%u%[%i%]%$$ is set to $cref nan$$. - - -$head Checking Optimization$$ -If $cref/NDEBUG/Faq/Speed/NDEBUG/$$ is not defined, -and $cref/f.size_order()/size_order/$$ is greater than zero, -a $cref forward_zero$$ calculation is done using the optimized version -of $icode f$$ and the results are checked to see that they are -the same as before. -If they are not the same, the -$cref ErrorHandler$$ is called with a known error message -related to $icode%f%.optimize()%$$. - -$head Example$$ -$children% - example/optimize.cpp -%$$ -The file -$cref optimize.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------ -*/ -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -namespace optimize { // BEGIN_CPPAD_OPTIMIZE_NAMESPACE -/*! -\file optimize.hpp -Routines for optimizing a tape -*/ - - -/*! -State for this variable set during reverse sweep. -*/ -enum enum_connect_type { - /// There is no operation that connects this variable to the - /// independent variables. - not_connected , - - /// There is one or more operations that connects this variable to the - /// independent variables. - yes_connected , - - /// There is only one parrent that connects this variable to the - /// independent variables and the parent is a summation operation; i.e., - /// AddvvOp, AddpvOp, SubpvOp, SubvpOp, or SubvvOp. - sum_connected , - - /// Satisfies the sum_connected assumptions above and in addition - /// this variable is the result of summation operator. - csum_connected , - - /// This node is only connected in the case where the comparision is - /// true for the conditional expression with index \c connect_index. - cexp_connected - -}; - -/*! -Class used to hold information about one conditional expression. -*/ -class class_cexp_pair { -public: - /// packs both the compare and index information - /// compare = pack_ % 2 - /// index = pack_ / 2 - size_t pack_; - - /// If this is true (false) this connection is only for the case where - /// the comparision in the conditional expression is true (false) - bool compare(void) const - { return pack_ % 2 != 0; } - - /// This is the index of the conditional expression (in cksip_info) - /// for this connection - size_t index(void) const - { return pack_ / 2; } - - /// constructor - class_cexp_pair(const bool& compare_arg, const size_t& index_arg) - : pack_(size_t(compare_arg) + 2 * index_arg ) - { CPPAD_ASSERT_UNKNOWN( compare_arg == compare() ); - CPPAD_ASSERT_UNKNOWN( index_arg == index() ); - } - - /// assignment operator - void operator=(const class_cexp_pair& right) - { pack_ = right.pack_; } - - /// not equal operator - bool operator!=(const class_cexp_pair& right) - { return pack_ != right.pack_; } - - /// Less than operator - /// (required for intersection of two sets of class_cexp_pair elements). - bool operator<(const class_cexp_pair& right) const - { return pack_ < right.pack_; } -}; - -/*! -A container that is like std::set except that it does -not allocate empty sets and only has a few operations. -*/ -class class_set_cexp_pair { -private: - // This set is empty if and only if ptr_ == CPPAD_NULL; - std::set* ptr_; - - void new_ptr(void) - { CPPAD_ASSERT_UNKNOWN( ptr_ == CPPAD_NULL ); - ptr_ = new std::set; - CPPAD_ASSERT_UNKNOWN( ptr_ != CPPAD_NULL ); - // std::cout << "new ptr_ = " << ptr_ << std::endl; - } - - void delete_ptr(void) - { if( ptr_ != CPPAD_NULL ) - { // std::cout << "delete ptr_ = " << ptr_ << std::endl; - delete ptr_; - } - ptr_ = CPPAD_NULL; - } - -public: - /// constructor - class_set_cexp_pair(void) - { ptr_ = CPPAD_NULL; } - - /// destructor - ~class_set_cexp_pair(void) - { delete_ptr(); } - - void print(void) - { if( ptr_ == CPPAD_NULL ) - { std::cout << "{ }"; - return; - } - CPPAD_ASSERT_UNKNOWN( ! empty() ); - const char* sep = "{ "; - std::set::const_iterator itr; - for(itr = ptr_->begin(); itr != ptr_->end(); itr++) - { std::cout << sep; - std::cout << "(" << itr->compare() << "," << itr->index() << ")"; - sep = ", "; - } - std::cout << "}"; - } - - /// assignment operator - void operator=(const class_set_cexp_pair& other) - { // make this a copy of the other set - if( other.ptr_ == CPPAD_NULL ) - { if( ptr_ == CPPAD_NULL ) - return; - delete_ptr(); - return; - } - CPPAD_ASSERT_UNKNOWN( ! other.empty() ); - if( ptr_ == CPPAD_NULL ) - new_ptr(); - *ptr_ = *other.ptr_; - } - - /// insert an element in this set - void insert(const class_cexp_pair& element) - { if( ptr_ == CPPAD_NULL ) - new_ptr(); - ptr_->insert(element); - CPPAD_ASSERT_UNKNOWN( ! empty() ); - } - - /// is this set empty - bool empty(void) const - { if( ptr_ == CPPAD_NULL ) - return true; - CPPAD_ASSERT_UNKNOWN( ! ptr_->empty() ); - return false; - } - - /// remove the elements in this set - void clear(void) - { if( ptr_ == CPPAD_NULL ) - return; - CPPAD_ASSERT_UNKNOWN( ! empty() ); - delete_ptr(); - } - - // returns begin pointer for the set - std::set::const_iterator begin(void) - { CPPAD_ASSERT_UNKNOWN( ! empty() ); - return ptr_->begin(); - } - - // returns end pointer for the set - std::set::const_iterator end(void) - { CPPAD_ASSERT_UNKNOWN( ! empty() ); - return ptr_->end(); - } - - /*! - Make this set the intersection of itself with another set. - - \param other - the other set - - */ - void intersection(const class_set_cexp_pair& other ) - { // empty result case - if( ptr_ == CPPAD_NULL ) - return; - - // empty result case - if( other.ptr_ == CPPAD_NULL ) - { delete_ptr(); - return; - } - - // put result here - class_set_cexp_pair result; - CPPAD_ASSERT_UNKNOWN( result.ptr_ == CPPAD_NULL ); - result.new_ptr(); - CPPAD_ASSERT_UNKNOWN( result.ptr_ != CPPAD_NULL ); - - // do the intersection - std::set_intersection( - ptr_->begin() , - ptr_->end() , - other.ptr_->begin() , - other.ptr_->end() , - std::inserter(*result.ptr_, result.ptr_->begin()) - ); - if( result.ptr_->empty() ) - result.delete_ptr(); - - // swap this and the result - std::swap(ptr_, result.ptr_); - - return; - } - -}; -/*! -Structure used by \c optimize to hold information about one variable. -in the old operation seqeunce. -*/ -struct struct_old_variable { - /// Operator for which this variable is the result, \c NumRes(op) > 0. - /// Set by the reverse sweep at beginning of optimization. - OpCode op; - - /// Pointer to first argument (child) for this operator. - /// Set by the reverse sweep at beginning of optimization. - const addr_t* arg; - - /// How is this variable connected to the independent variables - enum_connect_type connect_type; - - /// New operation sequence corresponding to this old varable. - /// Set during forward sweep to the index in the new tape - addr_t new_var; - - /// New operator index for this varable. - /// Set during forward sweep to the index in the new tape - size_t new_op; - - /// Did this variable match another variable in the operation sequence - bool match; -}; - -struct struct_size_pair { - size_t i_op; // an operator index - size_t i_var; // a variable index -}; - -/*! -Structures used by \c record_csum -to hold information about one variable. -*/ -struct struct_csum_variable { - /// Operator for which this variable is the result, \c NumRes(op) > 0. - OpCode op; - - /// Pointer to first argument (child) for this operator. - /// Set by the reverse sweep at beginning of optimization. - const addr_t* arg; - - /// Is this variable added to the summation - /// (if not it is subtracted) - bool add; -}; - -/*! -Structure used to pass work space from \c optimize to \c record_csum -(so that stacks do not start from zero size every time). -*/ -struct struct_csum_stacks { - /// stack of operations in the cummulative summation - std::stack op_stack; - /// stack of variables to be added - std::stack add_stack; - /// stack of variables to be subtracted - std::stack sub_stack; -}; - -/*! -CExpOp information that is copied to corresponding CSkipOp -*/ -struct struct_cskip_info { - /// comparision operator - CompareOp cop; - /// (flag & 1) is true if and only if left is a variable - /// (flag & 2) is true if and only if right is a variable - size_t flag; - /// index for left comparison operand - size_t left; - /// index for right comparison operand - size_t right; - /// maximum variable index between left and right - size_t max_left_right; - /// set of variables to skip on true - CppAD::vector skip_var_true; - /// set of variables to skip on false - CppAD::vector skip_var_false; - /// set of operations to skip on true - CppAD::vector skip_op_true; - /// set of operations to skip on false - CppAD::vector skip_op_false; - /// size of skip_op_true - size_t n_op_true; - /// size of skip_op_false - size_t n_op_false; - /// index in the argument recording of first argument for this CSkipOp - size_t i_arg; -}; -/*! -Connection information for a user atomic function -*/ -struct struct_user_info { - /// type of connection for this atomic function - enum_connect_type connect_type; - /// If this is an conditional connection, this is the information - /// of the correpsonding CondExpOp operators - class_set_cexp_pair cexp_set; - /// If this is a conditional connection, this is the operator - /// index of the beginning of the atomic call sequence; i.e., - /// the first UserOp. - size_t op_begin; - /// If this is a conditional connection, this is one more than the - /// operator index of the ending of the atomic call sequence; i.e., - /// the second UserOp. - size_t op_end; -}; - -/*! -Shared documentation for optimization helper functions (not called). - - -\param tape -is a vector that maps a variable index, in the old operation sequence, -to an struct_old_variable information record. -Note that the index for this vector must be greater than or equal zero and -less than tape.size(). - -\li tape[i].op -is the operator in the old operation sequence -corresponding to the old variable index \c i. -Assertion: NumRes(tape[i].op) > 0. - -\li tape[i].arg -for j < NumArg( tape[i].op ), tape[i].arg[j] -is the j-th the argument, in the old operation sequence, -corresponding to the old variable index \c i. -Assertion: tape[i].arg[j] < i. - -\li tape[i].new_var -Suppose -i <= current, j < NumArg( tape[i].op ), and k = tape[i].arg[j], -and \c j corresponds to a variable for operator tape[i].op. -It follows that tape[k].new_var -has alread been set to the variable in the new operation sequence -corresponding to the old variable index \c k. -This means that the \c new_var value has been set -for all the possible arguments that come before \a current. - -\param current -is the index in the old operation sequence for -the variable corresponding to the result for the current operator. -Assertions: - -current < tape.size(), -NumRes( tape[current].op ) > 0. - - -\param npar -is the number of parameters corresponding to this operation sequence. - -\param par -is a vector of length \a npar containing the parameters -for this operation sequence; i.e., -given a parameter index \c i, the corresponding parameter value is -par[i]. - -*/ -template -void prototype( - const CppAD::vector& tape , - size_t current , - size_t npar , - const Base* par ) -{ CPPAD_ASSERT_UNKNOWN(false); } - -/*! -Check a unary operator for a complete match with a previous operator. - -A complete match means that the result of the previous operator -can be used inplace of the result for current operator. - - -\param tape -is a vector that maps a variable index, in the old operation sequence, -to an struct_old_variable information record. -Note that the index for this vector must be greater than or equal zero and -less than tape.size(). - -\li tape[i].op -is the operator in the old operation sequence -corresponding to the old variable index \c i. -Assertion: NumRes(tape[i].op) > 0. - -\li tape[i].arg -for j < NumArg( tape[i].op ), tape[i].arg[j] -is the j-th the argument, in the old operation sequence, -corresponding to the old variable index \c i. -Assertion: tape[i].arg[j] < i. - -\li tape[i].new_var -Suppose -i <= current, j < NumArg( tape[i].op ), and k = tape[i].arg[j], -and \c j corresponds to a variable for operator tape[i].op. -It follows that tape[k].new_var -has alread been set to the variable in the new operation sequence -corresponding to the old variable index \c k. -This means that the \c new_var value has been set -for all the possible arguments that come before \a current. - -\param current -is the index in the old operation sequence for -the variable corresponding to the result for the current operator. -Assertions: - -current < tape.size(), -NumRes( tape[current].op ) > 0. - - -\param npar -is the number of parameters corresponding to this operation sequence. - -\param par -is a vector of length \a npar containing the parameters -for this operation sequence; i.e., -given a parameter index \c i, the corresponding parameter value is -par[i]. - - -\param hash_table_var -is a vector with size CPPAD_HASH_TABLE_SIZE -that maps a hash code to the corresponding -variable index in the old operation sequence. -All the values in this table must be less than \a current. - -\param code -The input value of code does not matter. -The output value of code is the hash code corresponding to -this operation in the new operation sequence. - -\return -If the return value is zero, -no match was found. -If the return value is greater than zero, -it is the old operation sequence index of a variable, -that comes before current and can be used to replace the current variable. - -\par Restrictions: -NumArg( tape[current].op ) == 1 -*/ -template -addr_t unary_match( - const CppAD::vector& tape , - size_t current , - size_t npar , - const Base* par , - const CppAD::vector& hash_table_var , - unsigned short& code ) -{ const addr_t* arg = tape[current].arg; - OpCode op = tape[current].op; - addr_t new_arg[1]; - - // ErfOp has three arguments, but the second and third are always the - // parameters 0 and 2 / sqrt(pi) respectively. - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 || op == ErfOp); - CPPAD_ASSERT_UNKNOWN( NumRes(op) > 0 ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < current ); - new_arg[0] = tape[arg[0]].new_var; - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < current ); - code = hash_code( - op , - new_arg , - npar , - par - ); - size_t i_var = hash_table_var[code]; - CPPAD_ASSERT_UNKNOWN( i_var < current ); - if( op == tape[i_var].op ) - { size_t k = tape[i_var].arg[0]; - CPPAD_ASSERT_UNKNOWN( k < i_var ); - if (new_arg[0] == tape[k].new_var ) - return i_var; - } - return 0; -} - -/*! -Check a binary operator for a complete match with a previous operator, - - -\param tape -is a vector that maps a variable index, in the old operation sequence, -to an struct_old_variable information record. -Note that the index for this vector must be greater than or equal zero and -less than tape.size(). - -\li tape[i].op -is the operator in the old operation sequence -corresponding to the old variable index \c i. -Assertion: NumRes(tape[i].op) > 0. - -\li tape[i].arg -for j < NumArg( tape[i].op ), tape[i].arg[j] -is the j-th the argument, in the old operation sequence, -corresponding to the old variable index \c i. -Assertion: tape[i].arg[j] < i. - -\li tape[i].new_var -Suppose -i <= current, j < NumArg( tape[i].op ), and k = tape[i].arg[j], -and \c j corresponds to a variable for operator tape[i].op. -It follows that tape[k].new_var -has alread been set to the variable in the new operation sequence -corresponding to the old variable index \c k. -This means that the \c new_var value has been set -for all the possible arguments that come before \a current. - -\param current -is the index in the old operation sequence for -the variable corresponding to the result for the current operator. -Assertions: - -current < tape.size(), -NumRes( tape[current].op ) > 0. - - -\param npar -is the number of parameters corresponding to this operation sequence. - -\param par -is a vector of length \a npar containing the parameters -for this operation sequence; i.e., -given a parameter index \c i, the corresponding parameter value is -par[i]. - - -\param hash_table_var -is a vector with size CPPAD_HASH_TABLE_SIZE -that maps a hash code to the corresponding -variable index in the old operation sequence. -All the values in this table must be less than \a current. - -\param code -The input value of code does not matter. -The output value of code is the hash code corresponding to -this operation in the new operation sequence. - -\return -If the return value is zero, -no match was found. -If the return value is greater than zero, -it is the index of a new variable that can be used to replace the -old variable. - - -\par Restrictions: -The binary operator must be an addition, subtraction, multiplication, division -or power operator. NumArg( tape[current].op ) == 1. -*/ -template -inline addr_t binary_match( - const CppAD::vector& tape , - size_t current , - size_t npar , - const Base* par , - const CppAD::vector& hash_table_var , - unsigned short& code ) -{ OpCode op = tape[current].op; - const addr_t* arg = tape[current].arg; - addr_t new_arg[2]; - bool parameter[2]; - - // initialize return value - addr_t match_var = 0; - - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(op) > 0 ); - switch(op) - { // index op variable - case DisOp: - // parameter not defined for this case - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < current ); - new_arg[0] = arg[0]; - new_arg[1] = tape[arg[1]].new_var; - break; - - // parameter op variable ---------------------------------- - case AddpvOp: - case MulpvOp: - case DivpvOp: - case PowpvOp: - case SubpvOp: - case ZmulpvOp: - // arg[0] - parameter[0] = true; - new_arg[0] = arg[0]; - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < npar ); - // arg[1] - parameter[1] = false; - new_arg[1] = tape[arg[1]].new_var; - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < current ); - break; - - // variable op parameter ----------------------------------- - case DivvpOp: - case PowvpOp: - case SubvpOp: - case ZmulvpOp: - // arg[0] - parameter[0] = false; - new_arg[0] = tape[arg[0]].new_var; - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < current ); - // arg[1] - parameter[1] = true; - new_arg[1] = arg[1]; - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < npar ); - break; - - // variable op variable ----------------------------------- - case AddvvOp: - case MulvvOp: - case DivvvOp: - case PowvvOp: - case SubvvOp: - case ZmulvvOp: - // arg[0] - parameter[0] = false; - new_arg[0] = tape[arg[0]].new_var; - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < current ); - // arg[1] - parameter[1] = false; - new_arg[1] = tape[arg[1]].new_var; - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < current ); - break; - - // must be one of the cases above - default: - CPPAD_ASSERT_UNKNOWN(false); - } - code = hash_code( - op , - new_arg , - npar , - par - ); - size_t i_var = hash_table_var[code]; - CPPAD_ASSERT_UNKNOWN( i_var < current ); - if( op == tape[i_var].op ) - { bool match = true; - if( op == DisOp ) - { match &= new_arg[0] == tape[i_var].arg[0]; - size_t k = tape[i_var].arg[1]; - match &= new_arg[1] == tape[k].new_var; - } - else - { for(size_t j = 0; j < 2; j++) - { size_t k = tape[i_var].arg[j]; - if( parameter[j] ) - { CPPAD_ASSERT_UNKNOWN( k < npar ); - match &= IdenticalEqualPar( - par[ arg[j] ], par[k] - ); - } - else - { CPPAD_ASSERT_UNKNOWN( k < i_var ); - match &= (new_arg[j] == tape[k].new_var); - } - } - } - if( match ) - match_var = i_var; - } - if( (match_var > 0) | ( (op != AddvvOp) & (op != MulvvOp ) ) ) - return match_var; - - // check for match with argument order switched ---------------------- - CPPAD_ASSERT_UNKNOWN( op == AddvvOp || op == MulvvOp ); - std::swap(new_arg[0], new_arg[1]); - unsigned short code_switch = hash_code( - op , - new_arg , - npar , - par - ); - i_var = hash_table_var[code_switch]; - CPPAD_ASSERT_UNKNOWN( i_var < current ); - if( op == tape[i_var].op ) - { bool match = true; - size_t j; - for(j = 0; j < 2; j++) - { size_t k = tape[i_var].arg[j]; - CPPAD_ASSERT_UNKNOWN( k < i_var ); - match &= (new_arg[j] == tape[k].new_var); - } - if( match ) - match_var = i_var; - } - return match_var; -} - -/*! -Record an operation of the form (parameter op variable). - - -\param tape -is a vector that maps a variable index, in the old operation sequence, -to an struct_old_variable information record. -Note that the index for this vector must be greater than or equal zero and -less than tape.size(). - -\li tape[i].op -is the operator in the old operation sequence -corresponding to the old variable index \c i. -Assertion: NumRes(tape[i].op) > 0. - -\li tape[i].arg -for j < NumArg( tape[i].op ), tape[i].arg[j] -is the j-th the argument, in the old operation sequence, -corresponding to the old variable index \c i. -Assertion: tape[i].arg[j] < i. - -\li tape[i].new_var -Suppose -i <= current, j < NumArg( tape[i].op ), and k = tape[i].arg[j], -and \c j corresponds to a variable for operator tape[i].op. -It follows that tape[k].new_var -has alread been set to the variable in the new operation sequence -corresponding to the old variable index \c k. -This means that the \c new_var value has been set -for all the possible arguments that come before \a current. - -\param current -is the index in the old operation sequence for -the variable corresponding to the result for the current operator. -Assertions: - -current < tape.size(), -NumRes( tape[current].op ) > 0. - - -\param npar -is the number of parameters corresponding to this operation sequence. - -\param par -is a vector of length \a npar containing the parameters -for this operation sequence; i.e., -given a parameter index \c i, the corresponding parameter value is -par[i]. - - -\param rec -is the object that will record the operations. - -\param op -is the operator that we are recording which must be one of the following: -AddpvOp, DivpvOp, MulpvOp, PowpvOp, SubpvOp, ZmulpvOp. - -\param arg -is the vector of arguments for this operator. - -\return -the result is the operaiton and variable index corresponding to the current -operation in the new operation sequence. -*/ -template -struct_size_pair record_pv( - const CppAD::vector& tape , - size_t current , - size_t npar , - const Base* par , - recorder* rec , - OpCode op , - const addr_t* arg ) -{ -# ifndef NDEBUG - switch(op) - { case AddpvOp: - case DivpvOp: - case MulpvOp: - case PowpvOp: - case SubpvOp: - case ZmulpvOp: - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } -# endif - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < npar ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < current ); - addr_t new_arg[2]; - new_arg[0] = rec->PutPar( par[arg[0]] ); - new_arg[1] = tape[ arg[1] ].new_var; - rec->PutArg( new_arg[0], new_arg[1] ); - - struct_size_pair ret; - ret.i_op = rec->num_op_rec(); - ret.i_var = rec->PutOp(op); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < ret.i_var ); - return ret; -} - - -/*! -Record an operation of the form (variable op parameter). - - -\param tape -is a vector that maps a variable index, in the old operation sequence, -to an struct_old_variable information record. -Note that the index for this vector must be greater than or equal zero and -less than tape.size(). - -\li tape[i].op -is the operator in the old operation sequence -corresponding to the old variable index \c i. -Assertion: NumRes(tape[i].op) > 0. - -\li tape[i].arg -for j < NumArg( tape[i].op ), tape[i].arg[j] -is the j-th the argument, in the old operation sequence, -corresponding to the old variable index \c i. -Assertion: tape[i].arg[j] < i. - -\li tape[i].new_var -Suppose -i <= current, j < NumArg( tape[i].op ), and k = tape[i].arg[j], -and \c j corresponds to a variable for operator tape[i].op. -It follows that tape[k].new_var -has alread been set to the variable in the new operation sequence -corresponding to the old variable index \c k. -This means that the \c new_var value has been set -for all the possible arguments that come before \a current. - -\param current -is the index in the old operation sequence for -the variable corresponding to the result for the current operator. -Assertions: - -current < tape.size(), -NumRes( tape[current].op ) > 0. - - -\param npar -is the number of parameters corresponding to this operation sequence. - -\param par -is a vector of length \a npar containing the parameters -for this operation sequence; i.e., -given a parameter index \c i, the corresponding parameter value is -par[i]. - - -\param rec -is the object that will record the operations. - -\param op -is the operator that we are recording which must be one of the following: -DivvpOp, PowvpOp, SubvpOp, ZmulvpOp. - -\param arg -is the vector of arguments for this operator. - -\return -the result operation and variable index corresponding to the current -operation in the new operation sequence. -*/ -template -struct_size_pair record_vp( - const CppAD::vector& tape , - size_t current , - size_t npar , - const Base* par , - recorder* rec , - OpCode op , - const addr_t* arg ) -{ -# ifndef NDEBUG - switch(op) - { case DivvpOp: - case PowvpOp: - case SubvpOp: - case ZmulvpOp: - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } -# endif - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < current ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < npar ); - addr_t new_arg[2]; - new_arg[0] = tape[ arg[0] ].new_var; - new_arg[1] = rec->PutPar( par[arg[1]] ); - rec->PutArg( new_arg[0], new_arg[1] ); - - struct_size_pair ret; - ret.i_op = rec->num_op_rec(); - ret.i_var = rec->PutOp(op); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < ret.i_var ); - return ret; -} - -/*! -Record an operation of the form (variable op variable). - - -\param tape -is a vector that maps a variable index, in the old operation sequence, -to an struct_old_variable information record. -Note that the index for this vector must be greater than or equal zero and -less than tape.size(). - -\li tape[i].op -is the operator in the old operation sequence -corresponding to the old variable index \c i. -Assertion: NumRes(tape[i].op) > 0. - -\li tape[i].arg -for j < NumArg( tape[i].op ), tape[i].arg[j] -is the j-th the argument, in the old operation sequence, -corresponding to the old variable index \c i. -Assertion: tape[i].arg[j] < i. - -\li tape[i].new_var -Suppose -i <= current, j < NumArg( tape[i].op ), and k = tape[i].arg[j], -and \c j corresponds to a variable for operator tape[i].op. -It follows that tape[k].new_var -has alread been set to the variable in the new operation sequence -corresponding to the old variable index \c k. -This means that the \c new_var value has been set -for all the possible arguments that come before \a current. - -\param current -is the index in the old operation sequence for -the variable corresponding to the result for the current operator. -Assertions: - -current < tape.size(), -NumRes( tape[current].op ) > 0. - - -\param npar -is the number of parameters corresponding to this operation sequence. - -\param par -is a vector of length \a npar containing the parameters -for this operation sequence; i.e., -given a parameter index \c i, the corresponding parameter value is -par[i]. - - -\param rec -is the object that will record the operations. - -\param op -is the operator that we are recording which must be one of the following: -AddvvOp, DivvvOp, MulvvOp, PowvvOp, SubvvOp, ZmulvvOp. - -\param arg -is the vector of arguments for this operator. - -\return -the result is the operation and variable index corresponding to the current -operation in the new operation sequence. -*/ -template -struct_size_pair record_vv( - const CppAD::vector& tape , - size_t current , - size_t npar , - const Base* par , - recorder* rec , - OpCode op , - const addr_t* arg ) -{ -# ifndef NDEBUG - switch(op) - { case AddvvOp: - case DivvvOp: - case MulvvOp: - case PowvvOp: - case SubvvOp: - case ZmulvvOp: - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } -# endif - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < current ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < current ); - addr_t new_arg[2]; - new_arg[0] = tape[ arg[0] ].new_var; - new_arg[1] = tape[ arg[1] ].new_var; - rec->PutArg( new_arg[0], new_arg[1] ); - - struct_size_pair ret; - ret.i_op = rec->num_op_rec(); - ret.i_var = rec->PutOp(op); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < ret.i_var ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[1]) < ret.i_var ); - return ret; -} - -// ========================================================================== - -/*! -Recording a cummulative cummulative summation starting at its highest parrent. - - -\param tape -is a vector that maps a variable index, in the old operation sequence, -to an struct_old_variable information record. -Note that the index for this vector must be greater than or equal zero and -less than tape.size(). - -\li tape[i].op -is the operator in the old operation sequence -corresponding to the old variable index \c i. -Assertion: NumRes(tape[i].op) > 0. - -\li tape[i].arg -for j < NumArg( tape[i].op ), tape[i].arg[j] -is the j-th the argument, in the old operation sequence, -corresponding to the old variable index \c i. -Assertion: tape[i].arg[j] < i. - -\li tape[i].new_var -Suppose -i <= current, j < NumArg( tape[i].op ), and k = tape[i].arg[j], -and \c j corresponds to a variable for operator tape[i].op. -It follows that tape[k].new_var -has alread been set to the variable in the new operation sequence -corresponding to the old variable index \c k. -This means that the \c new_var value has been set -for all the possible arguments that come before \a current. - -\param current -is the index in the old operation sequence for -the variable corresponding to the result for the current operator. -Assertions: - -current < tape.size(), -NumRes( tape[current].op ) > 0. - - -\param npar -is the number of parameters corresponding to this operation sequence. - -\param par -is a vector of length \a npar containing the parameters -for this operation sequence; i.e., -given a parameter index \c i, the corresponding parameter value is -par[i]. - - -\param rec -is the object that will record the operations. - -\param work -Is used for computation. On input and output, -work.op_stack.empty(), -work.add_stack.empty(), and -work.sub_stack.empty(), -are all true true. -These stacks are passed in so that elements can be allocated once -and then the elements can be reused with calls to \c record_csum. - -\par Exception -tape[i].new_var -is not yet defined for any node \c i that is \c csum_connected -to the \a current node -(or that is \c sum_connected to a node that is \c csum_connected). -For example; suppose that index \c j corresponds to a variable -in the current operator, -i = tape[current].arg[j], -and -tape[arg[j]].connect_type == csum_connected. -It then follows that -tape[i].new_var == tape.size(). - -\par Restriction: -\li tape[current].op -must be one of AddpvOp, AddvvOp, SubpvOp, SubvpOp, SubvvOp. - -\li tape[current].connect_type must be \c yes_connected. - -\li tape[j].connect_type == csum_connected for some index -j that is a variable operand for the current operation. -*/ - - -template -struct_size_pair record_csum( - const CppAD::vector& tape , - size_t current , - size_t npar , - const Base* par , - recorder* rec , - struct_csum_stacks& work ) -{ - - CPPAD_ASSERT_UNKNOWN( work.op_stack.empty() ); - CPPAD_ASSERT_UNKNOWN( work.add_stack.empty() ); - CPPAD_ASSERT_UNKNOWN( work.sub_stack.empty() ); - CPPAD_ASSERT_UNKNOWN( tape[current].connect_type == yes_connected ); - - size_t i; - OpCode op; - const addr_t* arg; - bool add; - struct struct_csum_variable var; - - var.op = tape[current].op; - var.arg = tape[current].arg; - var.add = true; - work.op_stack.push( var ); - Base sum_par(0); - -# ifndef NDEBUG - bool ok = false; - if( var.op == SubvpOp ) - ok = tape[ tape[current].arg[0] ].connect_type == csum_connected; - if( var.op == AddpvOp || var.op == SubpvOp ) - ok = tape[ tape[current].arg[1] ].connect_type == csum_connected; - if( var.op == AddvvOp || var.op == SubvvOp ) - { ok = tape[ tape[current].arg[0] ].connect_type == csum_connected; - ok |= tape[ tape[current].arg[1] ].connect_type == csum_connected; - } - CPPAD_ASSERT_UNKNOWN( ok ); -# endif - while( ! work.op_stack.empty() ) - { var = work.op_stack.top(); - work.op_stack.pop(); - op = var.op; - arg = var.arg; - add = var.add; - // process first argument to this operator - switch(op) - { case AddpvOp: - case SubpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < npar ); - if( add ) - sum_par += par[arg[0]]; - else sum_par -= par[arg[0]]; - break; - - case AddvvOp: - case SubvpOp: - case SubvvOp: - if( tape[arg[0]].connect_type == csum_connected ) - { CPPAD_ASSERT_UNKNOWN( - size_t(tape[arg[0]].new_var) == tape.size() - ); - var.op = tape[arg[0]].op; - var.arg = tape[arg[0]].arg; - var.add = add; - work.op_stack.push( var ); - } - else if( add ) - work.add_stack.push(arg[0]); - else work.sub_stack.push(arg[0]); - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } - // process second argument to this operator - switch(op) - { - case SubvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < npar ); - if( add ) - sum_par -= par[arg[1]]; - else sum_par += par[arg[1]]; - break; - - case SubvvOp: - case SubpvOp: - add = ! add; - - case AddvvOp: - case AddpvOp: - if( tape[arg[1]].connect_type == csum_connected ) - { CPPAD_ASSERT_UNKNOWN( - size_t(tape[arg[1]].new_var) == tape.size() - ); - var.op = tape[arg[1]].op; - var.arg = tape[arg[1]].arg; - var.add = add; - work.op_stack.push( var ); - } - else if( add ) - work.add_stack.push(arg[1]); - else work.sub_stack.push(arg[1]); - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } - } - // number of variables in this cummulative sum operator - size_t n_add = work.add_stack.size(); - size_t n_sub = work.sub_stack.size(); - size_t old_arg, new_arg; - rec->PutArg(n_add); // arg[0] - rec->PutArg(n_sub); // arg[1] - new_arg = rec->PutPar( sum_par ); - rec->PutArg(new_arg); // arg[2] - for(i = 0; i < n_add; i++) - { CPPAD_ASSERT_UNKNOWN( ! work.add_stack.empty() ); - old_arg = work.add_stack.top(); - new_arg = tape[old_arg].new_var; - CPPAD_ASSERT_UNKNOWN( new_arg < tape.size() ); - rec->PutArg(new_arg); // arg[3+i] - work.add_stack.pop(); - } - for(i = 0; i < n_sub; i++) - { CPPAD_ASSERT_UNKNOWN( ! work.sub_stack.empty() ); - old_arg = work.sub_stack.top(); - new_arg = tape[old_arg].new_var; - CPPAD_ASSERT_UNKNOWN( new_arg < tape.size() ); - rec->PutArg(new_arg); // arg[3 + arg[0] + i] - work.sub_stack.pop(); - } - rec->PutArg(n_add + n_sub); // arg[3 + arg[0] + arg[1]] - - - struct_size_pair ret; - ret.i_op = rec->num_op_rec(); - ret.i_var = rec->PutOp(CSumOp); - CPPAD_ASSERT_UNKNOWN( new_arg < ret.i_var ); - return ret; -} -// ========================================================================== -/*! -Convert a player object to an optimized recorder object - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param options -The possible values for this string are: -"", "no_conditional_skip". -If it is "no_conditional_skip", then no conditional skip operations -will be generated. - -\param n -is the number of independent variables on the tape. - -\param dep_taddr -On input this vector contains the indices for each of the dependent -variable values in the operation sequence corresponding to \a play. -Upon return it contains the indices for the same variables but in -the operation sequence corresponding to \a rec. - -\param play -This is the operation sequence that we are optimizing. -It is essentially const, except for play back state which -changes while it plays back the operation seqeunce. - -\param rec -The input contents of this recording does not matter. -Upon return, it contains an optimized verison of the -operation sequence corresponding to \a play. -*/ - -template -void optimize_run( - const std::string& options , - size_t n , - CppAD::vector& dep_taddr , - player* play , - recorder* rec ) -{ - // nan with type Base - Base base_nan = Base( std::numeric_limits::quiet_NaN() ); - - // temporary indices - size_t i, j, k; - - // check options - bool conditional_skip = - options.find("no_conditional_skip", 0) == std::string::npos; - - // temporary variables - OpCode op; // current operator - const addr_t* arg; // operator arguments - size_t i_var; // index of first result for current operator - - // range and domain dimensions for F - size_t m = dep_taddr.size(); - - // number of variables in the player - const size_t num_var = play->num_var_rec(); - -# ifndef NDEBUG - // number of parameters in the player - const size_t num_par = play->num_par_rec(); -# endif - - // number of VecAD indices - size_t num_vecad_ind = play->num_vec_ind_rec(); - - // number of VecAD vectors - size_t num_vecad_vec = play->num_vecad_vec_rec(); - - // ------------------------------------------------------------- - // data structure that maps variable index in original operation - // sequence to corresponding operator information - CppAD::vector tape(num_var); - - // if tape[i].connect_type == exp_connected, cexp_set[i] is the - // corresponding information for the conditional connection. - CppAD::vector cexp_vec_set; - if( conditional_skip ) - cexp_vec_set.resize(num_var); - // ------------------------------------------------------------- - // Determine how each variable is connected to the dependent variables - - // initialize all variables has having no connections - for(i = 0; i < num_var; i++) - tape[i].connect_type = not_connected; - - for(j = 0; j < m; j++) - { // mark dependent variables as having one or more connections - tape[ dep_taddr[j] ].connect_type = yes_connected; - } - - // vecad_connect contains a value for each VecAD object. - // vecad maps a VecAD index (which corresponds to the beginning of the - // VecAD object) to the vecad_connect falg for the VecAD object. - CppAD::vector vecad_connect(num_vecad_vec); - CppAD::vector vecad(num_vecad_ind); - j = 0; - for(i = 0; i < num_vecad_vec; i++) - { vecad_connect[i] = not_connected; - // length of this VecAD - size_t length = play->GetVecInd(j); - // set to proper index for this VecAD - vecad[j] = i; - for(k = 1; k <= length; k++) - vecad[j+k] = num_vecad_vec; // invalid index - // start of next VecAD - j += length + 1; - } - CPPAD_ASSERT_UNKNOWN( j == num_vecad_ind ); - - // work space used by UserOp. - typedef std::set size_set; - // - vector user_r_set; // set sparsity pattern for result - vector user_s_set; // set sparisty pattern for argument - // - vector user_r_bool; // bool sparsity pattern for result - vector user_s_bool; // bool sparisty pattern for argument - // - vectorBool user_r_pack; // pack sparsity pattern for result - vectorBool user_s_pack; // pack sparisty pattern for argument - // - size_t user_q = 0; // column dimension for sparsity patterns - size_t user_index = 0; // indentifier for this user_atomic operation - size_t user_id = 0; // user identifier for this call to operator - size_t user_i = 0; // index in result vector - size_t user_j = 0; // index in argument vector - size_t user_m = 0; // size of result vector - size_t user_n = 0; // size of arugment vector - // - atomic_base* user_atom = CPPAD_NULL; // current user atomic function - bool user_pack = false; // sparsity pattern type is pack - bool user_bool = false; // sparsity pattern type is bool - bool user_set = false; // sparsity pattern type is set - - // next expected operator in a UserOp sequence - enum { user_start, user_arg, user_ret, user_end } user_state; - - // During reverse mode, compute type of connection for each call to - // a user atomic function. - CppAD::vector user_info; - size_t user_curr = 0; - - /// During reverse mode, information for each CSkip operation - CppAD::vector cskip_info; - - // Initialize a reverse mode sweep through the operation sequence - size_t i_op; - play->reverse_start(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( op == EndOp ); - size_t mask; - user_state = user_end; - while(op != BeginOp) - { // next op - play->reverse_next(op, arg, i_op, i_var); - - // Store the operator corresponding to each variable - if( NumRes(op) > 0 ) - { tape[i_var].op = op; - tape[i_var].arg = arg; - } -# ifndef NDEBUG - if( i_op <= n ) - { CPPAD_ASSERT_UNKNOWN((op == InvOp) | (op == BeginOp)); - } - else CPPAD_ASSERT_UNKNOWN((op != InvOp) & (op != BeginOp)); -# endif - enum_connect_type connect_type = tape[i_var].connect_type; - class_set_cexp_pair* cexp_set = CPPAD_NULL; - if( conditional_skip ) - cexp_set = &cexp_vec_set[i_var]; - switch( op ) - { - // One variable corresponding to arg[0] - case AbsOp: - case AcosOp: - case AcoshOp: - case AsinOp: - case AsinhOp: - case AtanOp: - case AtanhOp: - case CosOp: - case CoshOp: - case DivvpOp: - case ErfOp: - case ExpOp: - case Expm1Op: - case LogOp: - case Log1pOp: - case PowvpOp: - case SignOp: - case SinOp: - case SinhOp: - case SqrtOp: - case TanOp: - case TanhOp: - case ZmulvpOp: - switch( connect_type ) - { case not_connected: - break; - - case yes_connected: - case sum_connected: - case csum_connected: - tape[arg[0]].connect_type = yes_connected; - break; - - case cexp_connected: - CPPAD_ASSERT_UNKNOWN( conditional_skip ) - if( tape[arg[0]].connect_type == not_connected ) - { tape[arg[0]].connect_type = cexp_connected; - cexp_vec_set[arg[0]] = *cexp_set; - } - else if( tape[arg[0]].connect_type == cexp_connected ) - { cexp_vec_set[arg[0]].intersection(*cexp_set); - if( cexp_vec_set[arg[0]].empty() ) - tape[arg[0]].connect_type = yes_connected; - } - else tape[arg[0]].connect_type = yes_connected; - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } - break; // -------------------------------------------- - - // One variable corresponding to arg[1] - case DisOp: - case DivpvOp: - case MulpvOp: - case PowpvOp: - case ZmulpvOp: - switch( connect_type ) - { case not_connected: - break; - - case yes_connected: - case sum_connected: - case csum_connected: - tape[arg[1]].connect_type = yes_connected; - break; - - case cexp_connected: - CPPAD_ASSERT_UNKNOWN( conditional_skip ) - if( tape[arg[1]].connect_type == not_connected ) - { tape[arg[1]].connect_type = cexp_connected; - cexp_vec_set[arg[1]] = *cexp_set; - } - else if( tape[arg[1]].connect_type == cexp_connected ) - { cexp_vec_set[arg[1]].intersection(*cexp_set); - if( cexp_vec_set[arg[1]].empty() ) - tape[arg[1]].connect_type = yes_connected; - } - else tape[arg[1]].connect_type = yes_connected; - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } - break; // -------------------------------------------- - - // Special case for SubvpOp - case SubvpOp: - switch( connect_type ) - { case not_connected: - break; - - case yes_connected: - case sum_connected: - case csum_connected: - if( tape[arg[0]].connect_type == not_connected ) - tape[arg[0]].connect_type = sum_connected; - else tape[arg[0]].connect_type = yes_connected; - break; - - case cexp_connected: - CPPAD_ASSERT_UNKNOWN( conditional_skip ) - if( tape[arg[0]].connect_type == not_connected ) - { tape[arg[0]].connect_type = cexp_connected; - cexp_vec_set[arg[0]] = *cexp_set; - } - else if( tape[arg[0]].connect_type == cexp_connected ) - { cexp_vec_set[arg[0]].intersection(*cexp_set); - if( cexp_vec_set[arg[0]].empty() ) - tape[arg[0]].connect_type = yes_connected; - } - else tape[arg[0]].connect_type = yes_connected; - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } - if( connect_type == sum_connected ) - { // convert sum to csum connection for this variable - tape[i_var].connect_type = connect_type = csum_connected; - } - break; // -------------------------------------------- - - // Special case for AddpvOp and SubpvOp - case AddpvOp: - case SubpvOp: - switch( connect_type ) - { case not_connected: - break; - - case yes_connected: - case sum_connected: - case csum_connected: - if( tape[arg[1]].connect_type == not_connected ) - tape[arg[1]].connect_type = sum_connected; - else tape[arg[1]].connect_type = yes_connected; - break; - - case cexp_connected: - CPPAD_ASSERT_UNKNOWN( conditional_skip ) - if( tape[arg[1]].connect_type == not_connected ) - { tape[arg[1]].connect_type = cexp_connected; - cexp_vec_set[arg[1]] = *cexp_set; - } - else if( tape[arg[1]].connect_type == cexp_connected ) - { cexp_vec_set[arg[1]].intersection(*cexp_set); - if( cexp_vec_set[arg[1]].empty() ) - tape[arg[1]].connect_type = yes_connected; - } - else tape[arg[1]].connect_type = yes_connected; - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } - if( connect_type == sum_connected ) - { // convert sum to csum connection for this variable - tape[i_var].connect_type = connect_type = csum_connected; - } - break; // -------------------------------------------- - - - // Special case for AddvvOp and SubvvOp - case AddvvOp: - case SubvvOp: - for(i = 0; i < 2; i++) switch( connect_type ) - { case not_connected: - break; - - case yes_connected: - case sum_connected: - case csum_connected: - if( tape[arg[i]].connect_type == not_connected ) - tape[arg[i]].connect_type = sum_connected; - else tape[arg[i]].connect_type = yes_connected; - break; - - case cexp_connected: - CPPAD_ASSERT_UNKNOWN( conditional_skip ) - if( tape[arg[i]].connect_type == not_connected ) - { tape[arg[i]].connect_type = cexp_connected; - cexp_vec_set[arg[i]] = *cexp_set; - } - else if( tape[arg[i]].connect_type == cexp_connected ) - { cexp_vec_set[arg[i]].intersection(*cexp_set); - if( cexp_vec_set[arg[i]].empty() ) - tape[arg[i]].connect_type = yes_connected; - } - else tape[arg[i]].connect_type = yes_connected; - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } - if( connect_type == sum_connected ) - { // convert sum to csum connection for this variable - tape[i_var].connect_type = connect_type = csum_connected; - } - break; // -------------------------------------------- - - // Other binary operators - // where operands are arg[0], arg[1] - case DivvvOp: - case MulvvOp: - case PowvvOp: - case ZmulvvOp: - for(i = 0; i < 2; i++) switch( connect_type ) - { case not_connected: - break; - - case yes_connected: - case sum_connected: - case csum_connected: - tape[arg[i]].connect_type = yes_connected; - break; - - case cexp_connected: - CPPAD_ASSERT_UNKNOWN( conditional_skip ) - if( tape[arg[i]].connect_type == not_connected ) - { tape[arg[i]].connect_type = cexp_connected; - cexp_vec_set[arg[i]] = *cexp_set; - } - else if( tape[arg[i]].connect_type == cexp_connected ) - { cexp_vec_set[arg[i]].intersection(*cexp_set); - if( cexp_vec_set[arg[i]].empty() ) - tape[arg[i]].connect_type = yes_connected; - } - else tape[arg[i]].connect_type = yes_connected; - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } - break; // -------------------------------------------- - - // Conditional expression operators - case CExpOp: - CPPAD_ASSERT_UNKNOWN( NumArg(CExpOp) == 6 ); - if( connect_type != not_connected ) - { struct_cskip_info info; - info.cop = CompareOp( arg[0] ); - info.flag = arg[1]; - info.left = arg[2]; - info.right = arg[3]; - info.n_op_true = 0; - info.n_op_false = 0; - info.i_arg = 0; // case where no CSkipOp for this CExpOp - // - size_t index = 0; - if( arg[1] & 1 ) - { index = std::max(index, info.left); - tape[info.left].connect_type = yes_connected; - } - if( arg[1] & 2 ) - { index = std::max(index, info.right); - tape[info.right].connect_type = yes_connected; - } - CPPAD_ASSERT_UNKNOWN( index > 0 ); - info.max_left_right = index; - // - index = cskip_info.size(); - cskip_info.push_back(info); - // - if( arg[1] & 4 ) - { if( conditional_skip && - tape[arg[4]].connect_type == not_connected ) - { tape[arg[4]].connect_type = cexp_connected; - cexp_vec_set[arg[4]] = *cexp_set; - cexp_vec_set[arg[4]].insert( - class_cexp_pair(true, index) - ); - } - else - { // if arg[4] is cexp_connected, it could be - // connected for both the true and false case - // 2DO: if previously cexp_connected - // and the true/false sense is the same, should - // keep this conditional connnection. - if(conditional_skip) - cexp_vec_set[arg[4]].clear(); - tape[arg[4]].connect_type = yes_connected; - } - } - if( arg[1] & 8 ) - { if( conditional_skip && - tape[arg[5]].connect_type == not_connected ) - { tape[arg[5]].connect_type = cexp_connected; - cexp_vec_set[arg[5]] = *cexp_set; - cexp_vec_set[arg[5]].insert( - class_cexp_pair(false, index) - ); - } - else - { if(conditional_skip) - cexp_vec_set[arg[5]].clear(); - tape[arg[5]].connect_type = yes_connected; - } - } - } - break; // -------------------------------------------- - - // Operations where there is nothing to do - case EndOp: - case ParOp: - case PriOp: - break; // -------------------------------------------- - - // Operators that never get removed - case BeginOp: - case InvOp: - tape[i_var].connect_type = yes_connected; - break; - - // Compare operators never get removed ----------------- - case LepvOp: - case LtpvOp: - case EqpvOp: - case NepvOp: - tape[arg[1]].connect_type = yes_connected; - break; - - case LevpOp: - case LtvpOp: - tape[arg[0]].connect_type = yes_connected; - break; - - case LevvOp: - case LtvvOp: - case EqvvOp: - case NevvOp: - tape[arg[0]].connect_type = yes_connected; - tape[arg[1]].connect_type = yes_connected; - break; - - // Load using a parameter index ---------------------- - case LdpOp: - if( tape[i_var].connect_type != not_connected ) - { - i = vecad[ arg[0] - 1 ]; - vecad_connect[i] = yes_connected; - } - break; // -------------------------------------------- - - // Load using a variable index - case LdvOp: - if( tape[i_var].connect_type != not_connected ) - { - i = vecad[ arg[0] - 1 ]; - vecad_connect[i] = yes_connected; - tape[arg[1]].connect_type = yes_connected; - } - break; // -------------------------------------------- - - // Store a variable using a parameter index - case StpvOp: - i = vecad[ arg[0] - 1 ]; - if( vecad_connect[i] != not_connected ) - tape[arg[2]].connect_type = yes_connected; - break; // -------------------------------------------- - - // Store a variable using a variable index - case StvvOp: - i = vecad[ arg[0] - 1 ]; - if( vecad_connect[i] ) - { tape[arg[1]].connect_type = yes_connected; - tape[arg[2]].connect_type = yes_connected; - } - break; - // ============================================================ - case UserOp: - // start or end atomic operation sequence - CPPAD_ASSERT_UNKNOWN( NumRes( UserOp ) == 0 ); - CPPAD_ASSERT_UNKNOWN( NumArg( UserOp ) == 4 ); - if( user_state == user_end ) - { user_index = arg[0]; - user_id = arg[1]; - user_n = arg[2]; - user_m = arg[3]; - user_q = 1; - user_atom = atomic_base::class_object(user_index); - if( user_atom == CPPAD_NULL ) - { std::string msg = - atomic_base::class_name(user_index) - + ": atomic_base function has been deleted"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } - user_pack = user_atom->sparsity() == - atomic_base::pack_sparsity_enum; - user_bool = user_atom->sparsity() == - atomic_base::bool_sparsity_enum; - user_set = user_atom->sparsity() == - atomic_base::set_sparsity_enum; - CPPAD_ASSERT_UNKNOWN( user_pack || user_bool || user_set ); - - user_set = user_atom->sparsity() == - atomic_base::set_sparsity_enum; - // - // Note user_q is 1, but use it for clarity of code - if( user_pack ) - { if( user_r_pack.size() != user_m * user_q ) - user_r_pack.resize( user_m * user_q ); - if( user_s_pack.size() != user_n * user_q ) - user_s_pack.resize( user_n * user_q ); - for(i = 0; i < user_m; i++) - for(j = 0; j < user_q; j++) - user_r_pack[ i * user_q + j] = false; - } - if( user_bool ) - { if( user_r_bool.size() != user_m * user_q ) - user_r_bool.resize( user_m * user_q ); - if( user_s_bool.size() != user_n * user_q ) - user_s_bool.resize( user_n * user_q ); - for(i = 0; i < user_m; i++) - for(j = 0; j < user_q; j++) - user_r_bool[ i * user_q + j] = false; - } - if( user_set ) - { if(user_s_set.size() != user_n ) - user_s_set.resize(user_n); - if(user_r_set.size() != user_m ) - user_r_set.resize(user_m); - for(i = 0; i < user_m; i++) - user_r_set[i].clear(); - } - // - user_j = user_n; - user_i = user_m; - user_state = user_ret; - // - struct_user_info info; - info.connect_type = not_connected; - info.op_end = i_op + 1; - user_info.push_back(info); - - } - else - { CPPAD_ASSERT_UNKNOWN( user_state == user_start ); - CPPAD_ASSERT_UNKNOWN( user_index == size_t(arg[0]) ); - CPPAD_ASSERT_UNKNOWN( user_id == size_t(arg[1]) ); - CPPAD_ASSERT_UNKNOWN( user_n == size_t(arg[2]) ); - CPPAD_ASSERT_UNKNOWN( user_m == size_t(arg[3]) ); - user_state = user_end; - // - CPPAD_ASSERT_UNKNOWN( user_curr + 1 == user_info.size() ); - user_info[user_curr].op_begin = i_op; - user_curr = user_info.size(); - } - break; - - case UsrapOp: - // parameter argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( 0 < user_j && user_j <= user_n ); - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - --user_j; - if( user_j == 0 ) - user_state = user_start; - break; - - case UsravOp: - // variable argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( 0 < user_j && user_j <= user_n ); - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) <= i_var ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - --user_j; - if( user_set ) - { if( ! user_s_set[user_j].empty() ) - tape[arg[0]].connect_type = - user_info[user_curr].connect_type; - } - if( user_bool ) - { if( user_s_bool[user_j] ) - tape[arg[0]].connect_type = - user_info[user_curr].connect_type; - } - if( user_pack ) - { if( user_s_pack[user_j] ) - tape[arg[0]].connect_type = - user_info[user_curr].connect_type; - } - if( user_j == 0 ) - user_state = user_start; - break; - - case UsrrvOp: - // variable result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( 0 < user_i && user_i <= user_m ); - --user_i; - switch( connect_type ) - { case not_connected: - break; - - case yes_connected: - case sum_connected: - case csum_connected: - user_info[user_curr].connect_type = yes_connected; - if( user_set ) - user_r_set[user_i].insert(0); - if( user_bool ) - user_r_bool[user_i] = true; - if( user_pack ) - user_r_pack[user_i] = true; - break; - - case cexp_connected: - CPPAD_ASSERT_UNKNOWN( conditional_skip ); - if( user_info[user_curr].connect_type == not_connected ) - { user_info[user_curr].connect_type = connect_type; - user_info[user_curr].cexp_set = *cexp_set; - } - else if(user_info[user_curr].connect_type==cexp_connected) - { user_info[user_curr].cexp_set.intersection(*cexp_set); - if( user_info[user_curr].cexp_set.empty() ) - user_info[user_curr].connect_type = yes_connected; - } - else user_info[user_curr].connect_type = yes_connected; - if( user_set ) - user_r_set[user_i].insert(0); - if( user_bool ) - user_r_bool[user_i] = true; - if( user_pack ) - user_r_pack[user_i] = true; - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } - // drop into op = UsrrpOp code to handle case where user_i == 0 - // for both UsrrvOp and UsrrpOp together. - - case UsrrpOp: - if( op == UsrrpOp ) - { // parameter result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( 0 < user_i && user_i <= user_m ); - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - --user_i; - } - if( user_i == 0 ) - { // call users function for this operation - user_atom->set_id(user_id); - bool flag = false; - if( user_set ) - { flag = user_atom-> - rev_sparse_jac(user_q, user_r_set, user_s_set); - } - if( user_bool ) - { flag = user_atom-> - rev_sparse_jac(user_q, user_r_bool, user_s_bool); - } - if( user_pack ) - { flag = user_atom-> - rev_sparse_jac(user_q, user_r_pack, user_s_pack); - } - if( ! flag ) - { std::string s = - "Optimizing an ADFun object" - " that contains the atomic function\n\t"; - s += user_atom->afun_name(); - s += "\nCurrent atomic_sparsity is set to"; - // - if( user_set ) - s += "set_sparsity_enum.\n"; - if( user_bool ) - s += "bool_sparsity_enum.\n"; - if( user_pack ) - s += "pack_sparsity_enum.\n"; - // - s += "This version of rev_sparse_jac returned false"; - CPPAD_ASSERT_KNOWN(false, s.c_str() ); - } - user_state = user_arg; - } - break; - // ============================================================ - - // all cases should be handled above - default: - CPPAD_ASSERT_UNKNOWN(0); - } - } - // values corresponding to BeginOp - CPPAD_ASSERT_UNKNOWN( i_op == 0 && i_var == 0 && op == BeginOp ); - tape[i_var].op = op; - tape[i_var].connect_type = yes_connected; - // ------------------------------------------------------------- - - // Determine which variables can be conditionally skipped - for(i = 0; i < num_var; i++) - { if( tape[i].connect_type == cexp_connected && - ! cexp_vec_set[i].empty() ) - { std::set::const_iterator itr = - cexp_vec_set[i].begin(); - while( itr != cexp_vec_set[i].end() ) - { j = itr->index(); - if( itr->compare() == true ) - cskip_info[j].skip_var_false.push_back(i); - else cskip_info[j].skip_var_true.push_back(i); - itr++; - } - } - } - // Determine size of skip information in user_info - for(i = 0; i < user_info.size(); i++) - { if( user_info[i].connect_type == cexp_connected && - ! user_info[i].cexp_set.empty() ) - { std::set::const_iterator itr = - user_info[i].cexp_set.begin(); - while( itr != user_info[i].cexp_set.end() ) - { j = itr->index(); - if( itr->compare() == true ) - cskip_info[j].n_op_false = - user_info[i].op_end - user_info[i].op_begin; - else - cskip_info[j].n_op_true = - user_info[i].op_end - user_info[i].op_begin; - itr++; - } - } - } - - // Sort the conditional skip information by the maximum of the - // index for the left and right comparision operands - CppAD::vector cskip_info_order( cskip_info.size() ); - { CppAD::vector keys( cskip_info.size() ); - for(i = 0; i < cskip_info.size(); i++) - keys[i] = std::max( cskip_info[i].left, cskip_info[i].right ); - CppAD::index_sort(keys, cskip_info_order); - } - // index in sorted order - size_t cskip_order_next = 0; - // index in order during reverse sweep - size_t cskip_info_index = cskip_info.size(); - - - // Initilaize table mapping hash code to variable index in tape - // as pointing to the BeginOp at the beginning of the tape - CppAD::vector hash_table_var(CPPAD_HASH_TABLE_SIZE); - for(i = 0; i < CPPAD_HASH_TABLE_SIZE; i++) - hash_table_var[i] = 0; - CPPAD_ASSERT_UNKNOWN( tape[0].op == BeginOp ); - - // initialize mapping from old variable index to new - // operator and variable index - for(i = 0; i < num_var; i++) - { tape[i].new_op = 0; // invalid index (except for BeginOp) - tape[i].new_var = num_var; // invalid index - } - - // Erase all information in the old recording - rec->free(); - - // initialize mapping from old VecAD index to new VecAD index - CppAD::vector new_vecad_ind(num_vecad_ind); - for(i = 0; i < num_vecad_ind; i++) - new_vecad_ind[i] = num_vecad_ind; // invalid index - - j = 0; // index into the old set of indices - for(i = 0; i < num_vecad_vec; i++) - { // length of this VecAD - size_t length = play->GetVecInd(j); - if( vecad_connect[i] != not_connected ) - { // Put this VecAD vector in new recording - CPPAD_ASSERT_UNKNOWN(length < num_vecad_ind); - new_vecad_ind[j] = rec->PutVecInd(length); - for(k = 1; k <= length; k++) new_vecad_ind[j+k] = - rec->PutVecInd( - rec->PutPar( - play->GetPar( - play->GetVecInd(j+k) - ) ) ); - } - // start of next VecAD - j += length + 1; - } - CPPAD_ASSERT_UNKNOWN( j == num_vecad_ind ); - - // start playing the operations in the forward direction - play->forward_start(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( user_curr == user_info.size() ); - - // playing forward skips BeginOp at the beginning, but not EndOp at - // the end. Put BeginOp at beginning of recording - CPPAD_ASSERT_UNKNOWN( op == BeginOp ); - CPPAD_ASSERT_NARG_NRES(BeginOp, 1, 1); - tape[i_var].new_op = rec->num_op_rec(); - tape[i_var].new_var = rec->PutOp(BeginOp); - rec->PutArg(0); - - - // temporary buffer for new argument values - addr_t new_arg[6]; - - // temporary work space used by record_csum - // (decalared here to avoid realloaction of memory) - struct_csum_stacks csum_work; - - // tempory used to hold a size_pair - struct_size_pair size_pair; - - user_state = user_start; - while(op != EndOp) - { // next op - play->forward_next(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( (i_op > n) | (op == InvOp) ); - CPPAD_ASSERT_UNKNOWN( (i_op <= n) | (op != InvOp) ); - - // determine if we should insert a conditional skip here - bool skip = cskip_order_next < cskip_info.size(); - skip &= op != BeginOp; - skip &= op != InvOp; - skip &= user_state == user_start; - if( skip ) - { j = cskip_info_order[cskip_order_next]; - if( NumRes(op) > 0 ) - skip &= cskip_info[j].max_left_right < i_var; - else - skip &= cskip_info[j].max_left_right <= i_var; - } - if( skip ) - { cskip_order_next++; - struct_cskip_info info = cskip_info[j]; - size_t n_true = info.skip_var_true.size() + info.n_op_true; - size_t n_false = info.skip_var_false.size() + info.n_op_false; - skip &= n_true > 0 || n_false > 0; - if( skip ) - { CPPAD_ASSERT_UNKNOWN( NumRes(CSkipOp) == 0 ); - size_t n_arg = 7 + n_true + n_false; - // reserve space for the arguments to this operator but - // delay setting them until we have all the new addresses - cskip_info[j].i_arg = rec->ReserveArg(n_arg); - CPPAD_ASSERT_UNKNOWN( cskip_info[j].i_arg > 0 ); - rec->PutOp(CSkipOp); - } - } - - // determine if we should keep this operation in the new - // operation sequence - bool keep; - switch( op ) - { // see wish_list/Optimize/CompareChange entry. - case EqpvOp: - case EqvvOp: - case LepvOp: - case LevpOp: - case LevvOp: - case LtpvOp: - case LtvpOp: - case LtvvOp: - case NepvOp: - case NevvOp: - keep = true; - break; - - case PriOp: - keep = false; - break; - - case InvOp: - case EndOp: - keep = true; - break; - - case StppOp: - case StvpOp: - case StpvOp: - case StvvOp: - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 0 ); - i = vecad[ arg[0] - 1 ]; - keep = vecad_connect[i] != not_connected; - break; - - case AddpvOp: - case AddvvOp: - case SubpvOp: - case SubvpOp: - case SubvvOp: - keep = tape[i_var].connect_type != not_connected; - keep &= tape[i_var].connect_type != csum_connected; - break; - - case UserOp: - case UsrapOp: - case UsravOp: - case UsrrpOp: - case UsrrvOp: - keep = true; - break; - - default: - keep = tape[i_var].connect_type != not_connected; - break; - } - - unsigned short code = 0; - bool replace_hash = false; - addr_t match_var; - tape[i_var].match = false; - if( keep ) switch( op ) - { - // Unary operator where operand is arg[0] - case AbsOp: - case AcosOp: - case AcoshOp: - case AsinOp: - case AsinhOp: - case AtanOp: - case AtanhOp: - case CosOp: - case CoshOp: - case ErfOp: - case ExpOp: - case Expm1Op: - case LogOp: - case Log1pOp: - case SignOp: - case SinOp: - case SinhOp: - case SqrtOp: - case TanOp: - case TanhOp: - match_var = unary_match( - tape , // inputs - i_var , - play->num_par_rec() , - play->GetPar() , - hash_table_var , - code // outputs - ); - if( match_var > 0 ) - { tape[i_var].match = true; - tape[match_var].match = true; - tape[i_var].new_var = tape[match_var].new_var; - } - else - { - replace_hash = true; - new_arg[0] = tape[ arg[0] ].new_var; - rec->PutArg( new_arg[0] ); - tape[i_var].new_op = rec->num_op_rec(); - tape[i_var].new_var = i = rec->PutOp(op); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < i ); - if( op == ErfOp ) - { // Error function is a special case - // second argument is always the parameter 0 - // third argument is always the parameter 2 / sqrt(pi) - CPPAD_ASSERT_UNKNOWN( NumArg(ErfOp) == 3 ); - rec->PutArg( rec->PutPar( Base(0) ) ); - rec->PutArg( rec->PutPar( - Base( 1.0 / std::sqrt( std::atan(1.0) ) ) - ) ); - } - } - break; - // --------------------------------------------------- - // Binary operators where - // left is a variable and right is a parameter - case SubvpOp: - if( tape[arg[0]].connect_type == csum_connected ) - { - // convert to a sequence of summation operators - size_pair = record_csum( - tape , // inputs - i_var , - play->num_par_rec() , - play->GetPar() , - rec , - csum_work - ); - tape[i_var].new_op = size_pair.i_op; - tape[i_var].new_var = size_pair.i_var; - // abort rest of this case - break; - } - case DivvpOp: - case PowvpOp: - case ZmulvpOp: - match_var = binary_match( - tape , // inputs - i_var , - play->num_par_rec() , - play->GetPar() , - hash_table_var , - code // outputs - ); - if( match_var > 0 ) - { tape[i_var].match = true; - tape[match_var].match = true; - tape[i_var].new_var = tape[match_var].new_var; - } - else - { size_pair = record_vp( - tape , // inputs - i_var , - play->num_par_rec() , - play->GetPar() , - rec , - op , - arg - ); - tape[i_var].new_op = size_pair.i_op; - tape[i_var].new_var = size_pair.i_var; - replace_hash = true; - } - break; - // --------------------------------------------------- - // Binary operators where - // left is an index and right is a variable - case DisOp: - match_var = binary_match( - tape , // inputs - i_var , - play->num_par_rec() , - play->GetPar() , - hash_table_var , - code // outputs - ); - if( match_var > 0 ) - { tape[i_var].match = true; - tape[match_var].match = true; - tape[i_var].new_var = tape[match_var].new_var; - } - else - { new_arg[0] = arg[0]; - new_arg[1] = tape[ arg[1] ].new_var; - rec->PutArg( new_arg[0], new_arg[1] ); - tape[i_var].new_op = rec->num_op_rec(); - tape[i_var].new_var = rec->PutOp(op); - CPPAD_ASSERT_UNKNOWN( - new_arg[1] < tape[i_var].new_var - ); - replace_hash = true; - } - break; - - // --------------------------------------------------- - // Binary operators where - // left is a parameter and right is a variable - case SubpvOp: - case AddpvOp: - if( tape[arg[1]].connect_type == csum_connected ) - { - // convert to a sequence of summation operators - size_pair = record_csum( - tape , // inputs - i_var , - play->num_par_rec() , - play->GetPar() , - rec , - csum_work - ); - tape[i_var].new_op = size_pair.i_op; - tape[i_var].new_var = size_pair.i_var; - // abort rest of this case - break; - } - case DivpvOp: - case MulpvOp: - case PowpvOp: - case ZmulpvOp: - match_var = binary_match( - tape , // inputs - i_var , - play->num_par_rec() , - play->GetPar() , - hash_table_var , - code // outputs - ); - if( match_var > 0 ) - { tape[i_var].match = true; - tape[match_var].match = true; - tape[i_var].new_var = tape[match_var].new_var; - } - else - { size_pair = record_pv( - tape , // inputs - i_var , - play->num_par_rec() , - play->GetPar() , - rec , - op , - arg - ); - tape[i_var].new_op = size_pair.i_op; - tape[i_var].new_var = size_pair.i_var; - replace_hash = true; - } - break; - // --------------------------------------------------- - // Binary operator where - // both operators are variables - case AddvvOp: - case SubvvOp: - if( (tape[arg[0]].connect_type == csum_connected) | - (tape[arg[1]].connect_type == csum_connected) - ) - { - // convert to a sequence of summation operators - size_pair = record_csum( - tape , // inputs - i_var , - play->num_par_rec() , - play->GetPar() , - rec , - csum_work - ); - tape[i_var].new_op = size_pair.i_op; - tape[i_var].new_var = size_pair.i_var; - // abort rest of this case - break; - } - case DivvvOp: - case MulvvOp: - case PowvvOp: - case ZmulvvOp: - match_var = binary_match( - tape , // inputs - i_var , - play->num_par_rec() , - play->GetPar() , - hash_table_var , - code // outputs - ); - if( match_var > 0 ) - { tape[i_var].match = true; - tape[match_var].match = true; - tape[i_var].new_var = tape[match_var].new_var; - } - else - { size_pair = record_vv( - tape , // inputs - i_var , - play->num_par_rec() , - play->GetPar() , - rec , - op , - arg - ); - tape[i_var].new_op = size_pair.i_op; - tape[i_var].new_var = size_pair.i_var; - replace_hash = true; - } - break; - // --------------------------------------------------- - // Conditional expression operators - case CExpOp: - CPPAD_ASSERT_NARG_NRES(op, 6, 1); - new_arg[0] = arg[0]; - new_arg[1] = arg[1]; - mask = 1; - for(i = 2; i < 6; i++) - { if( arg[1] & mask ) - { new_arg[i] = tape[arg[i]].new_var; - CPPAD_ASSERT_UNKNOWN( - size_t(new_arg[i]) < num_var - ); - } - else new_arg[i] = rec->PutPar( - play->GetPar( arg[i] ) - ); - mask = mask << 1; - } - rec->PutArg( - new_arg[0] , - new_arg[1] , - new_arg[2] , - new_arg[3] , - new_arg[4] , - new_arg[5] - ); - tape[i_var].new_op = rec->num_op_rec(); - tape[i_var].new_var = rec->PutOp(op); - // - // The new addresses for left and right are used during - // fill in the arguments for the CSkip operations. This does not - // affect max_left_right which is used during this sweep. - CPPAD_ASSERT_UNKNOWN( cskip_info_index > 0 ); - cskip_info_index--; - cskip_info[ cskip_info_index ].left = new_arg[2]; - cskip_info[ cskip_info_index ].right = new_arg[3]; - break; - // --------------------------------------------------- - // Operations with no arguments and no results - case EndOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 0); - rec->PutOp(op); - break; - // --------------------------------------------------- - // Operations with two arguments and no results - case LepvOp: - case LtpvOp: - case EqpvOp: - case NepvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 0); - new_arg[0] = rec->PutPar( play->GetPar(arg[0]) ); - new_arg[1] = tape[arg[1]].new_var; - rec->PutArg(new_arg[0], new_arg[1]); - rec->PutOp(op); - break; - // - case LevpOp: - case LtvpOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 0); - new_arg[0] = tape[arg[0]].new_var; - new_arg[1] = rec->PutPar( play->GetPar(arg[1]) ); - rec->PutArg(new_arg[0], new_arg[1]); - rec->PutOp(op); - break; - // - case LevvOp: - case LtvvOp: - case EqvvOp: - case NevvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 0); - new_arg[0] = tape[arg[0]].new_var; - new_arg[1] = tape[arg[1]].new_var; - rec->PutArg(new_arg[0], new_arg[1]); - rec->PutOp(op); - break; - - // --------------------------------------------------- - // Operations with no arguments and one result - case InvOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 1); - tape[i_var].new_op = rec->num_op_rec(); - tape[i_var].new_var = rec->PutOp(op); - break; - // --------------------------------------------------- - // Operations with one argument that is a parameter - case ParOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - new_arg[0] = rec->PutPar( play->GetPar(arg[0] ) ); - - rec->PutArg( new_arg[0] ); - tape[i_var].new_op = rec->num_op_rec(); - tape[i_var].new_var = rec->PutOp(op); - break; - // --------------------------------------------------- - // Load using a parameter index - case LdpOp: - CPPAD_ASSERT_NARG_NRES(op, 3, 1); - new_arg[0] = new_vecad_ind[ arg[0] ]; - new_arg[1] = arg[1]; - new_arg[2] = rec->num_load_op_rec(); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < num_vecad_ind ); - rec->PutArg( - new_arg[0], - new_arg[1], - new_arg[2] - ); - tape[i_var].new_op = rec->num_op_rec(); - tape[i_var].new_var = rec->PutLoadOp(op); - break; - // --------------------------------------------------- - // Load using a variable index - case LdvOp: - CPPAD_ASSERT_NARG_NRES(op, 3, 1); - new_arg[0] = new_vecad_ind[ arg[0] ]; - new_arg[1] = tape[arg[1]].new_var; - new_arg[2] = rec->num_load_op_rec(); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < num_vecad_ind ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[1]) < num_var ); - rec->PutArg( - new_arg[0], - new_arg[1], - new_arg[2] - ); - tape[i_var].new_var = rec->num_op_rec(); - tape[i_var].new_var = rec->PutLoadOp(op); - break; - // --------------------------------------------------- - // Store a parameter using a parameter index - case StppOp: - CPPAD_ASSERT_NARG_NRES(op, 3, 0); - new_arg[0] = new_vecad_ind[ arg[0] ]; - new_arg[1] = rec->PutPar( play->GetPar(arg[1]) ); - new_arg[2] = rec->PutPar( play->GetPar(arg[2]) ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < num_vecad_ind ); - rec->PutArg( - new_arg[0], - new_arg[1], - new_arg[2] - ); - rec->PutOp(op); - break; - // --------------------------------------------------- - // Store a parameter using a variable index - case StvpOp: - CPPAD_ASSERT_NARG_NRES(op, 3, 0); - new_arg[0] = new_vecad_ind[ arg[0] ]; - new_arg[1] = tape[arg[1]].new_var; - new_arg[2] = rec->PutPar( play->GetPar(arg[2]) ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < num_vecad_ind ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[1]) < num_var ); - rec->PutArg( - new_arg[0], - new_arg[1], - new_arg[2] - ); - rec->PutOp(op); - break; - // --------------------------------------------------- - // Store a variable using a parameter index - case StpvOp: - CPPAD_ASSERT_NARG_NRES(op, 3, 0); - new_arg[0] = new_vecad_ind[ arg[0] ]; - new_arg[1] = rec->PutPar( play->GetPar(arg[1]) ); - new_arg[2] = tape[arg[2]].new_var; - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < num_vecad_ind ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[1]) < num_var ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[2]) < num_var ); - rec->PutArg( - new_arg[0], - new_arg[1], - new_arg[2] - ); - rec->PutOp(op); - break; - // --------------------------------------------------- - // Store a variable using a variable index - case StvvOp: - CPPAD_ASSERT_NARG_NRES(op, 3, 0); - new_arg[0] = new_vecad_ind[ arg[0] ]; - new_arg[1] = tape[arg[1]].new_var; - new_arg[2] = tape[arg[2]].new_var; - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < num_vecad_ind ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[1]) < num_var ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[2]) < num_var ); - rec->PutArg( - new_arg[0], - new_arg[1], - new_arg[2] - ); - rec->PutOp(op); - break; - - // ----------------------------------------------------------- - case UserOp: - CPPAD_ASSERT_NARG_NRES(op, 4, 0); - if( user_state == user_start ) - { user_state = user_arg; - CPPAD_ASSERT_UNKNOWN( user_curr > 0 ); - user_curr--; - user_info[user_curr].op_begin = rec->num_op_rec(); - } - else - { user_state = user_start; - user_info[user_curr].op_end = rec->num_op_rec() + 1; - } - // user_index, user_id, user_n, user_m - if( user_info[user_curr].connect_type != not_connected ) - { rec->PutArg(arg[0], arg[1], arg[2], arg[3]); - rec->PutOp(UserOp); - } - break; - - case UsrapOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 0); - if( user_info[user_curr].connect_type != not_connected ) - { new_arg[0] = rec->PutPar( play->GetPar(arg[0]) ); - rec->PutArg(new_arg[0]); - rec->PutOp(UsrapOp); - } - break; - - case UsravOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 0); - if( user_info[user_curr].connect_type != not_connected ) - { new_arg[0] = tape[arg[0]].new_var; - if( size_t(new_arg[0]) < num_var ) - { rec->PutArg(new_arg[0]); - rec->PutOp(UsravOp); - } - else - { // This argument does not affect the result and - // has been optimized out so use nan in its place. - new_arg[0] = rec->PutPar( base_nan ); - rec->PutArg(new_arg[0]); - rec->PutOp(UsrapOp); - } - } - break; - - case UsrrpOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 0); - if( user_info[user_curr].connect_type != not_connected ) - { new_arg[0] = rec->PutPar( play->GetPar(arg[0]) ); - rec->PutArg(new_arg[0]); - rec->PutOp(UsrrpOp); - } - break; - - case UsrrvOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 1); - if( user_info[user_curr].connect_type != not_connected ) - { tape[i_var].new_op = rec->num_op_rec(); - tape[i_var].new_var = rec->PutOp(UsrrvOp); - } - break; - // --------------------------------------------------- - - // all cases should be handled above - default: - CPPAD_ASSERT_UNKNOWN(false); - - } - if( replace_hash ) - { // The old variable index i_var corresponds to the - // new variable index tape[i_var].new_var. In addition - // this is the most recent variable that has this code. - hash_table_var[code] = i_var; - } - - } - // modify the dependent variable vector to new indices - for(i = 0; i < dep_taddr.size(); i++ ) - { CPPAD_ASSERT_UNKNOWN( size_t(tape[dep_taddr[i]].new_var) < num_var ); - dep_taddr[i] = tape[ dep_taddr[i] ].new_var; - } - -# ifndef NDEBUG - size_t num_new_op = rec->num_op_rec(); - for(i_var = 0; i_var < tape.size(); i_var++) - CPPAD_ASSERT_UNKNOWN( tape[i_var].new_op < num_new_op ); -# endif - - // Move skip information from user_info to cskip_info - for(i = 0; i < user_info.size(); i++) - { if( user_info[i].connect_type == cexp_connected && - ! user_info[i].cexp_set.empty() ) - { std::set::const_iterator itr = - user_info[i].cexp_set.begin(); - while( itr != user_info[i].cexp_set.end() ) - { j = itr->index(); - k = user_info[i].op_begin; - while(k < user_info[i].op_end) - { if( itr->compare() == true ) - cskip_info[j].skip_op_false.push_back(k++); - else cskip_info[j].skip_op_true.push_back(k++); - } - itr++; - } - } - } - - // fill in the arguments for the CSkip operations - CPPAD_ASSERT_UNKNOWN( cskip_order_next == cskip_info.size() ); - for(i = 0; i < cskip_info.size(); i++) - { struct_cskip_info info = cskip_info[i]; - if( info.i_arg > 0 ) - { CPPAD_ASSERT_UNKNOWN( info.n_op_true==info.skip_op_true.size() ); - CPPAD_ASSERT_UNKNOWN(info.n_op_false==info.skip_op_false.size()); - size_t n_true = - info.skip_var_true.size() + info.skip_op_true.size(); - size_t n_false = - info.skip_var_false.size() + info.skip_op_false.size(); - size_t i_arg = info.i_arg; - rec->ReplaceArg(i_arg++, info.cop ); - rec->ReplaceArg(i_arg++, info.flag ); - rec->ReplaceArg(i_arg++, info.left ); - rec->ReplaceArg(i_arg++, info.right ); - rec->ReplaceArg(i_arg++, n_true ); - rec->ReplaceArg(i_arg++, n_false ); - for(j = 0; j < info.skip_var_true.size(); j++) - { i_var = info.skip_var_true[j]; - if( tape[i_var].match ) - { // The operation for this argument has been removed, - // so use an operator index that never comes up. - rec->ReplaceArg(i_arg++, rec->num_op_rec()); - } - else - { CPPAD_ASSERT_UNKNOWN( tape[i_var].new_op > 0 ); - rec->ReplaceArg(i_arg++, tape[i_var].new_op ); - } - } - for(j = 0; j < info.skip_op_true.size(); j++) - { i_op = info.skip_op_true[j]; - rec->ReplaceArg(i_arg++, i_op); - } - for(j = 0; j < info.skip_var_false.size(); j++) - { i_var = info.skip_var_false[j]; - if( tape[i_var].match ) - { // The operation for this argument has been removed, - // so use an operator index that never comes up. - rec->ReplaceArg(i_arg++, rec->num_op_rec()); - } - else - { CPPAD_ASSERT_UNKNOWN( tape[i_var].new_op > 0 ); - rec->ReplaceArg(i_arg++, tape[i_var].new_op ); - } - } - for(j = 0; j < info.skip_op_false.size(); j++) - { i_op = info.skip_op_false[j]; - rec->ReplaceArg(i_arg++, i_op); - } - rec->ReplaceArg(i_arg++, n_true + n_false); -# ifndef NDEBUG - size_t n_arg = 7 + n_true + n_false; - CPPAD_ASSERT_UNKNOWN( info.i_arg + n_arg == i_arg ); -# endif - } - } -} - -} // END_CPPAD_OPTIMIZE_NAMESPACE - -/*! -Optimize a player object operation sequence - -The operation sequence for this object is replaced by one with fewer operations -but the same funcition and derivative values. - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param options -The default value for this option is the empty string. -The only other possible value is "no_conditional_skip". -If this option is present, no conditional skip operators will be generated. - -*/ -template -void ADFun::optimize(const std::string& options) -{ // place to store the optimized version of the recording - recorder rec; - - // number of independent variables - size_t n = ind_taddr_.size(); - -# ifndef NDEBUG - size_t i, j, m = dep_taddr_.size(); - CppAD::vector x(n), y(m), check(m); - Base max_taylor(0); - bool check_zero_order = num_order_taylor_ > 0; - if( check_zero_order ) - { // zero order coefficients for independent vars - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( play_.GetOp(j+1) == InvOp ); - CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] == j+1 ); - x[j] = taylor_[ ind_taddr_[j] * cap_order_taylor_ + 0]; - } - // zero order coefficients for dependent vars - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - y[i] = taylor_[ dep_taddr_[i] * cap_order_taylor_ + 0]; - } - // maximum zero order coefficient not counting BeginOp at beginning - // (which is correpsonds to uninitialized memory). - for(i = 1; i < num_var_tape_; i++) - { if( abs_geq(taylor_[i*cap_order_taylor_+0] , max_taylor) ) - max_taylor = taylor_[i*cap_order_taylor_+0]; - } - } -# endif - - // create the optimized recording - CppAD::optimize::optimize_run(options, n, dep_taddr_, &play_, &rec); - - // number of variables in the recording - num_var_tape_ = rec.num_var_rec(); - - // now replace the recording - play_.get(rec); - - // set flag so this function knows it has been optimized - has_been_optimized_ = true; - - // free memory allocated for sparse Jacobian calculation - // (the results are no longer valid) - for_jac_sparse_pack_.resize(0, 0); - for_jac_sparse_set_.resize(0,0); - - // free old Taylor coefficient memory - taylor_.free(); - num_order_taylor_ = 0; - cap_order_taylor_ = 0; - - // resize and initilaize conditional skip vector - // (must use player size because it now has the recoreder information) - cskip_op_.erase(); - cskip_op_.extend( play_.num_op_rec() ); - -# ifndef NDEBUG - if( check_zero_order ) - { - // zero order forward calculation using new operation sequence - check = Forward(0, x); - - // check results - Base eps = 10. * CppAD::numeric_limits::epsilon(); - for(i = 0; i < m; i++) CPPAD_ASSERT_KNOWN( - abs_geq( eps * max_taylor , check[i] - y[i] ) , - "Error during check of f.optimize()." - ); - - // Erase memory that this calculation was done so NDEBUG gives - // same final state for this object (from users perspective) - num_order_taylor_ = 0; - } -# endif -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize/cskip_info.hpp b/ct_core/include/ct/external/cppad/local/optimize/cskip_info.hpp deleted file mode 100644 index a11d01cd7..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize/cskip_info.hpp +++ /dev/null @@ -1,72 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_OPTIMIZE_CSKIP_INFO_HPP -# define CPPAD_LOCAL_OPTIMIZE_CSKIP_INFO_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include // defines CompareOp -# include - -/*! -\file cskip_info.hpp -Information about one conditional expression. -*/ - -// BEGIN_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -namespace CppAD { namespace local { namespace optimize { -/*! -Information about one conditional expression. -*/ -struct struct_cskip_info { - /// The operator index for this conditional expression operation - size_t i_op; - - /// (flag & 1) is true if and only if left is a variable - /// (flag & 2) is true if and only if right is a variable - size_t flag; - - /// variable or parameter index for left comparison operand - size_t left; - - /// variable or parameter index for right comparison operand - size_t right; - - /// maximum variable index between left and right (ignoring parameters). - size_t max_left_right; - - /// set of operator that are not used when comparison result is true - /// Note that UsrapOp, UsravOp, UsrrpOp, and UsrrvOp, are not in this - /// vector and should be skipped when the corresponding UserOp are skipped. - CppAD::vector skip_op_true; - - /// set of variables that are not used when comparison result is false - /// Note that UsrapOp, UsravOp, UsrrpOp, and UsrrvOp, are not in this - /// vector and should be skipped when the corresponding UserOp are skipped. - CppAD::vector skip_op_false; - - /// comparision operator for this conditional expression - CompareOp cop; -}; - -// Information about the conditional skip in the new operation sequence -struct struct_cskip_new { - /// new variable or parameter index for left comparison operand - size_t left; - /// new variable or parameter index for right comparison operand - size_t right; - /// maximum variable index between left and right (ignoring parameters). - size_t max_left_right; - /// index where this conditional skips arguments start - size_t i_arg; -}; - -} } } // END_CPPAD_LOCAL_OPTIMIZE_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize/csum_stacks.hpp b/ct_core/include/ct/external/cppad/local/optimize/csum_stacks.hpp deleted file mode 100644 index b7d8a6801..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize/csum_stacks.hpp +++ /dev/null @@ -1,38 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_OPTIMIZE_CSUM_STACKS_HPP -# define CPPAD_LOCAL_OPTIMIZE_CSUM_STACKS_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include - -/*! -\file csum_stacks.hpp -Information about one cumulative summation operation. -*/ - -// BEGIN_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -namespace CppAD { namespace local { namespace optimize { -/*! -Information about one cumulative summation operation. -*/ -struct struct_csum_stacks { - /// old operator indices for this cummulative summation - std::stack op_stack; - /// old variable indices to be added - std::stack add_stack; - /// old variavle indices to be subtracted - std::stack sub_stack; -}; - -} } } // END_CPPAD_LOCAL_OPTIMIZE_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize/csum_variable.hpp b/ct_core/include/ct/external/cppad/local/optimize/csum_variable.hpp deleted file mode 100644 index fbe21929e..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize/csum_variable.hpp +++ /dev/null @@ -1,42 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_OPTIMIZE_CSUM_VARIABLE_HPP -# define CPPAD_LOCAL_OPTIMIZE_CSUM_VARIABLE_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include // defines addr_t - -/*! -\file csum_variable.hpp -Information about one old variable that is part of a new CSumOp operation. -*/ - -// BEGIN_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -namespace CppAD { namespace local { namespace optimize { -/*! -Information about one old variable that is part of a new CSumOp operation. -*/ -struct struct_csum_variable { - /// Pointer to first argument (child) for this old operator. - /// Set by the reverse sweep at beginning of optimization. - const addr_t* arg; - - /// Was this old variable added to the summation - /// (if not it was subtracted) - bool add; - - /// Operator for which this old variable is the result, NumRes(op) > 0. - OpCode op; -}; - -} } } // END_CPPAD_LOCAL_OPTIMIZE_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize/get_op_info.hpp b/ct_core/include/ct/external/cppad/local/optimize/get_op_info.hpp deleted file mode 100644 index 66b14b20c..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize/get_op_info.hpp +++ /dev/null @@ -1,1074 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_OPTIMIZE_GET_OP_INFO_HPP -# define CPPAD_LOCAL_OPTIMIZE_GET_OP_INFO_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/*! -\file op_info.hpp -Create operator information tables -*/ - -# include -# include -# include -# include - -// BEGIN_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -namespace CppAD { namespace local { namespace optimize { - -/// Is this an addition or subtraction operator -inline bool add_or_subtract(OpCode op) -{ bool result; - switch(op) - { - case AddpvOp: - case AddvvOp: - case SubpvOp: - case SubvpOp: - case SubvvOp: - result = true; - break; - - default: - result = false; - break; - } - return result; -} - - -/*! -Increarse argument usage and propagate cexp_set from parent to argument. - -\param sum_parent -is parent an addition or subtraction operator (passed for speed so -do not need to call add_or_subtract for parent). - -\param i_parent -is the operator index for the parent operator. - -\param i_arg -is the operator index for the argument to the parent operator. - -\param op_info -structure that holds the information for each of the operators. -The output value of op_info[i_arg].usage is increased; to be specific, -If sum_parent is true and the input value of op_info[i_arg].usage -is no_usage, its output value is csum_usage. -Otherwise, the output value of op_info[i_arg].usage is yes_usage. - -\param cexp_set -This is a vector of sets with one set for each operator. We denote -the i-th set by set[i]. - -\li -In the special case where cexp_set.n_set() is zero, -cexp_set is not changed. - -\li -If cexp_set.n_set() != 0 and op_info[i_arg].usage == no_usage, -the input value of set[i_arg] must be empty. -In this case the output value if set[i_arg] is equal to set[i_parent] -(which may also be empty). - -\li -If cexp_set.n_set() != 0 and op_info[i_arg].usage != no_usage, -the output value of set[i_arg] is the intersection of -its input value and set[i_parent]. -*/ -inline void usage_cexp_parent2arg( - bool sum_parent , - size_t i_parent , - size_t i_arg , - vector& op_info , - sparse_pack& cexp_set ) -{ - // cexp_set - if( cexp_set.n_set() > 0 ) - { if( op_info[i_arg].usage == no_usage ) - { // set[i_arg] = set[i_parent] - cexp_set.assignment(i_arg, i_parent, cexp_set); - } - else - { // set[i_arg] = set[i_arg] intersect set[i_parent] - cexp_set.binary_intersection(i_arg, i_arg, i_parent, cexp_set); - } - } - // usage - bool csum = sum_parent && op_info[i_arg].usage == no_usage; - if( csum ) - csum = add_or_subtract( op_info[i_arg].op ); - if( csum ) - op_info[i_arg].usage = csum_usage; - else - op_info[i_arg].usage = yes_usage; - // - return; -} - -/*! -Get variable to operator map and operator basic operator information - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param conditional_skip -If conditional_skip this is true, the conditional skip information -cskip_info will be calculated. -This may be time intensive and may not have much benefit in the optimized -recording. - -\param compare_op -if this is true, arguments are considered used if they appear in compare -operators. This is a side effect because compare operators have boolean -results (and the result is not in the tape; i.e. NumRes(op) is zero -for these operators. (This is an example of a side effect.) - -\param print_for_op -if this is true, arguments are considered used if they appear in -print forward operators; i.e., PriOp. -This is also a side effect; i.e. NumRes(PriOp) is zero. - -\param play -This is the operation sequence. -It is essentially const, except for play back state which -changes while it plays back the operation seqeunce. - -\param dep_taddr -is a vector of variable indices for the dependent variables. - -\param var2op -The input size of this vector must be zero. -Upone return it has size equal to the number of variables -in the operation sequence; i.e., num_var = play->nun_var_rec(). -It maps each variable index to the operator that created the variable. -This is only true for the primary variables. -If the index i_var corresponds to an auxillary variable, var2op[i_var] -is equalt to num_op (which is not a valid operator index). - -\param cskip_info -The input size of this vector must be zero. -If conditional_skip is false, cskip_info is not changed. -Otherwise, -upon return cskip_info has size equal to the number of conditional expressions -in the operation sequence; i.e., the number of CExpOp operators. -The value cskip_info[j] is the information corresponding to the j-th -conditional expression in the operation sequence. -This vector is in the same order as the operation sequence; i.e. -if j1 > j2, cskip_info[j1].i_op > cskip_info[j2].i_op. - -\param vecad_used -The input size of this vector must be zero. -Upon retun it has size equal to the number of VecAD vectors -in the operations sequences; i.e., play->num_vecad_vec_rec(). -The VecAD vectors are indexed in the order that thier indices apprear -in the one large play->GetVecInd that holds all the VecAD vectors. - -\param op_info -The input size of this vector must be zero. -Upon return it has size equal to the number of operators -in the operation sequence; i.e., num_op = play->nun_var_rec(). -The value op_info[i] -have been set to the values corresponding to the i-th operator -in the operation sequence. -*/ - -template -void get_op_info( - bool conditional_skip , - bool compare_op , - bool print_for_op , - player* play , - const vector& dep_taddr , - vector& var2op , - vector& cskip_info , - vector& vecad_used , - vector& op_info ) -{ - CPPAD_ASSERT_UNKNOWN( var2op.size() == 0 ); - CPPAD_ASSERT_UNKNOWN( cskip_info.size() == 0 ); - CPPAD_ASSERT_UNKNOWN( vecad_used.size() == 0 ); - CPPAD_ASSERT_UNKNOWN( op_info.size() == 0 ); - - // number of operators in the tape - const size_t num_op = play->num_op_rec(); - op_info.resize( num_op ); - // - // number of variables in the tape - const size_t num_var = play->num_var_rec(); - var2op.resize( num_var ); - // - // initialize mapping from variable index to operator index - for(size_t i = 0; i < num_var; i++) - var2op[i] = num_op; // invalid (used for auxillary variables) - // - // information set by forward_user - size_t user_old=0, user_m=0, user_n=0, user_i=0, user_j=0; - enum_user_state user_state; - // - // information set by forward_next - OpCode op; // operator - const addr_t* arg; // arguments - size_t i_op; // operator index - size_t i_var; // variable index of first result - // - // ---------------------------------------------------------------------- - // Forward pass to compute op, arg, i_var for each operator and var2op - // ---------------------------------------------------------------------- - play->forward_start(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( op == BeginOp ); - CPPAD_ASSERT_UNKNOWN( NumRes(BeginOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( i_op == 0 ); - CPPAD_ASSERT_UNKNOWN( i_var == 0 ); - op_info[i_op].op = op; - op_info[i_op].arg = arg; - op_info[i_op].i_var = i_var; - // - // This variaible index, 0, is automatically created, but it should - // not used because variable index 0 represents a paraemeter during - // the recording process. So we set - var2op[i_var] = num_op; - // - size_t num_cexp_op = 0; - user_state = start_user; - while(op != EndOp) - { // next operator - play->forward_next(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( - size_t( std::numeric_limits::max() ) > i_var - ); - // - // information for this operator - op_info[i_op].op = op; - op_info[i_op].arg = arg; - op_info[i_op].i_var = i_var; - // - // mapping from variable index to operator index - if( NumRes(op) > 0 ) - var2op[i_var] = i_op; - // - switch( op ) - { case CSumOp: - // must correct arg before next operator - play->forward_csum(op, arg, i_op, i_var); - break; - - case CSkipOp: - // must correct arg before next operator - play->forward_csum(op, arg, i_op, i_var); - break; - - case UserOp: - case UsrapOp: - case UsravOp: - case UsrrpOp: - case UsrrvOp: - play->forward_user(op, user_state, - user_old, user_m, user_n, user_i, user_j - ); - break; - - case CExpOp: - // Set the operator index for this conditional expression and - // count the number of conditional expressions. - ++num_cexp_op; - break; - - default: - break; - } - } - // vector that maps conditional expression index to operator index - vector cexp2op( num_cexp_op ); - // ---------------------------------------------------------------------- - // Reverse pass to compute usage and cexp_set for each operator - // ---------------------------------------------------------------------- - // work space used by user defined atomic functions - typedef std::set size_set; - vector user_x; // parameters in x as integers - vector user_ix; // variables indices for argument vector - vector user_r_set; // set sparsity pattern for result - vector user_s_set; // set sparisty pattern for argument - vector user_r_bool; // bool sparsity pattern for result - vector user_s_bool; // bool sparisty pattern for argument - vectorBool user_r_pack; // pack sparsity pattern for result - vectorBool user_s_pack; // pack sparisty pattern for argument - // - atomic_base* user_atom = CPPAD_NULL; // current user atomic function - bool user_pack = false; // sparsity pattern type is pack - bool user_bool = false; // sparsity pattern type is bool - bool user_set = false; // sparsity pattern type is set - // ----------------------------------------------------------------------- - // vecad information - size_t num_vecad = play->num_vecad_vec_rec(); - size_t num_vecad_ind = play->num_vec_ind_rec(); - // - vecad_used.resize(num_vecad); - for(size_t i = 0; i < num_vecad; i++) - vecad_used[i] = false; - // - vector arg2vecad(num_vecad_ind); - for(size_t i = 0; i < num_vecad_ind; i++) - arg2vecad[i] = num_vecad; // invalid value - size_t arg_0 = 1; // value of arg[0] for theh first vecad - for(size_t i = 0; i < num_vecad; i++) - { - // mapping from arg[0] value to index for this vecad object. - arg2vecad[arg_0] = i; - // - // length of this vecad object - size_t length = play->GetVecInd(arg_0 - 1); - // - // set to proper index in GetVecInd for next VecAD arg[0] value - arg_0 += length + 1; - } - CPPAD_ASSERT_UNKNOWN( arg_0 == num_vecad_ind + 1 ); - // ----------------------------------------------------------------------- - // parameter information (used by atomic function calls) - size_t num_par = play->num_par_rec(); - const Base* parameter = CPPAD_NULL; - if( num_par > 0 ) - parameter = play->GetPar(); - // ----------------------------------------------------------------------- - // Set of conditional expressions comparisons that usage of each - /// operator depends on. The operator can be skipped if any of the - // comparisons results in the set holds. A set for operator i_op is - // not defined and left empty when op_info[i_op].usage = no_usage. - /// It is also left empty for the result of any VecAD operations. - sparse_pack cexp_set; - // - // number of sets - size_t num_set = 0; - if( conditional_skip && num_cexp_op > 0) - num_set = num_op; - // - // conditional expression index = element / 2 - // conditional expression compare = bool ( element % 2) - size_t end_set = 2 * num_cexp_op; - // - cexp_set.resize(num_set, end_set); - // ----------------------------------------------------------------------- - // - // initialize operator usage - for(size_t i = 0; i < num_op; i++) - op_info[i].usage = no_usage; - for(size_t i = 0; i < dep_taddr.size(); i++) - { i_op = var2op[ dep_taddr[i] ]; - op_info[i_op].usage = yes_usage; // dependent variables - } - // - // Initialize reverse pass - size_t last_user_i_op = 0; - size_t cexp_index = num_cexp_op; - user_state = end_user; - i_op = num_op; - while(i_op != 0 ) - { --i_op; - // - // this operator information - op = op_info[i_op].op; - arg = op_info[i_op].arg; - i_var = op_info[i_op].i_var; - // - // Is the result of this operation used. - // (This only makes sense when NumRes(op) > 0.) - enum_usage use_result = op_info[i_op].usage; - // - bool sum_op = false; - switch( op ) - { - // ============================================================= - // normal operators - // ============================================================= - - // Only one variable with index arg[0] - case SubvpOp: - sum_op = true; - // - case AbsOp: - case AcosOp: - case AcoshOp: - case AsinOp: - case AsinhOp: - case AtanOp: - case AtanhOp: - case CosOp: - case CoshOp: - case DivvpOp: - case ErfOp: - case ExpOp: - case Expm1Op: - case LogOp: - case Log1pOp: - case PowvpOp: - case SignOp: - case SinOp: - case SinhOp: - case SqrtOp: - case TanOp: - case TanhOp: - case ZmulvpOp: - CPPAD_ASSERT_UNKNOWN( NumRes(op) > 0 ); - if( use_result != no_usage ) - { size_t j_op = var2op[ arg[0] ]; - usage_cexp_parent2arg(sum_op, i_op, j_op, op_info, cexp_set); - } - break; // -------------------------------------------- - - // Only one variable with index arg[1] - case AddpvOp: - case SubpvOp: - sum_op = true; - // - case DisOp: - case DivpvOp: - case MulpvOp: - case PowpvOp: - case ZmulpvOp: - CPPAD_ASSERT_UNKNOWN( NumRes(op) > 0 ); - if( use_result != no_usage ) - { size_t j_op = var2op[ arg[1] ]; - usage_cexp_parent2arg(sum_op, i_op, j_op, op_info, cexp_set); - } - break; // -------------------------------------------- - - // arg[0] and arg[1] are the only variables - case AddvvOp: - case SubvvOp: - sum_op = true; - // - case DivvvOp: - case MulvvOp: - case PowvvOp: - case ZmulvvOp: - CPPAD_ASSERT_UNKNOWN( NumRes(op) > 0 ); - if( use_result != no_usage ) - { for(size_t i = 0; i < 2; i++) - { size_t j_op = var2op[ arg[i] ]; - usage_cexp_parent2arg( - sum_op, i_op, j_op, op_info, cexp_set - ); - } - } - break; // -------------------------------------------- - - // Conditional expression operators - // arg[2], arg[3], arg[4], arg[5] are parameters or variables - case CExpOp: - --cexp_index; - cexp2op[ cexp_index ] = i_op; - CPPAD_ASSERT_UNKNOWN( NumRes(op) > 0 ); - if( use_result != no_usage ) - { CPPAD_ASSERT_UNKNOWN( NumArg(CExpOp) == 6 ); - addr_t mask[] = {1, 2, 4, 8}; - for(size_t i = 0; i < 4; i++) - { if( arg[1] & mask[i] ) - { size_t j_op = var2op[ arg[2 + i] ]; - usage_cexp_parent2arg( - sum_op, i_op, j_op, op_info, cexp_set - ); - } - } - // here is where we add elements to cexp_set - if( conditional_skip ) - { bool same_variable = bool(arg[1] & 4) && bool(arg[1] & 8); - same_variable &= arg[4] == arg[5]; - if( ( arg[1] & 4 ) && (! same_variable) ) - { // arg[4] is a variable - size_t j_op = var2op[ arg[4] ]; - CPPAD_ASSERT_UNKNOWN(op_info[j_op].usage != no_usage); - // j_op corresponds to the value used when the - // comparison result is true. It can be skipped when - // the comparison is false (0). - size_t element = 2 * cexp_index + 0; - cexp_set.add_element(j_op, element); - } - if( ( arg[1] & 8 ) && (! same_variable) ) - { // arg[5] is a variable - size_t j_op = var2op[ arg[5] ]; - CPPAD_ASSERT_UNKNOWN(op_info[j_op].usage != no_usage); - // j_op corresponds to the value used when the - // comparison result is false. It can be skipped when - // the comparison is true (1). - size_t element = 2 * cexp_index + 1; - cexp_set.add_element(j_op, element); - } - } - } - break; // -------------------------------------------- - - // Operations that are never used - // (new CSkip options are generated if conditional_skip is true) - case CSkipOp: - case ParOp: - break; - - // Operators that are always used - case InvOp: - case BeginOp: - case EndOp: - op_info[i_op].usage = yes_usage; - break; // ----------------------------------------------- - - // The print forward operator - case PriOp: - CPPAD_ASSERT_NARG_NRES(op, 5, 0); - if( print_for_op ) - { op_info[i_op].usage = yes_usage; - if( arg[0] & 1 ) - { // arg[1] is a variable - size_t j_op = var2op[ arg[1] ]; - usage_cexp_parent2arg( - sum_op, i_op, j_op, op_info, cexp_set - ); - } - if( arg[0] & 2 ) - { // arg[3] is a variable - size_t j_op = var2op[ arg[3] ]; - usage_cexp_parent2arg( - sum_op, i_op, j_op, op_info, cexp_set - ); - } - } - break; // ----------------------------------------------------- - - // ============================================================= - // Comparison operators - // ============================================================= - - // Compare operators where arg[1] is only variable - case LepvOp: - case LtpvOp: - case EqpvOp: - case NepvOp: - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 0 ); - if( compare_op ) - { op_info[i_op].usage = yes_usage; - // - size_t j_op = var2op[ arg[1] ]; - usage_cexp_parent2arg(sum_op, i_op, j_op, op_info, cexp_set); - } - break; // ---------------------------------------------- - - // Compare operators where arg[0] is only variable - case LevpOp: - case LtvpOp: - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 0 ); - if( compare_op ) - { op_info[i_op].usage = yes_usage; - // - size_t j_op = var2op[ arg[0] ]; - usage_cexp_parent2arg(sum_op, i_op, j_op, op_info, cexp_set); - } - break; // ---------------------------------------------- - - // Compare operators where arg[0] and arg[1] are variables - case LevvOp: - case LtvvOp: - case EqvvOp: - case NevvOp: - if( compare_op ) - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 0 ); - if( compare_op ) - { op_info[i_op].usage = yes_usage; - // - for(size_t i = 0; i < 2; i++) - { size_t j_op = var2op[ arg[i] ]; - usage_cexp_parent2arg( - sum_op, i_op, j_op, op_info, cexp_set - ); - } - } - break; // ---------------------------------------------- - - // ============================================================= - // VecAD operators - // ============================================================= - - // load operator using a parameter index - case LdpOp: - CPPAD_ASSERT_UNKNOWN( NumRes(op) > 0 ); - if( use_result != no_usage ) - { size_t i_vec = arg2vecad[ arg[0] ]; - vecad_used[i_vec] = true; - } - break; // -------------------------------------------- - - // load operator using a variable index - case LdvOp: - CPPAD_ASSERT_UNKNOWN( NumRes(op) > 0 ); - if( use_result != no_usage ) - { size_t i_vec = arg2vecad[ arg[0] ]; - vecad_used[i_vec] = true; - // - size_t j_op = var2op[ arg[1] ]; - op_info[j_op].usage = yes_usage; - } - break; // -------------------------------------------- - - // Store a variable using a parameter index - case StpvOp: - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 0 ); - if( vecad_used[ arg2vecad[ arg[0] ] ] ) - { op_info[i_op].usage = yes_usage; - // - size_t j_op = var2op[ arg[2] ]; - op_info[j_op].usage = yes_usage; - } - break; // -------------------------------------------- - - // Store a variable using a variable index - case StvvOp: - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 0 ); - if( vecad_used[ arg2vecad[ arg[0] ] ] ) - { op_info[i_op].usage = yes_usage; - // - size_t j_op = var2op[ arg[1] ]; - op_info[j_op].usage = yes_usage; - size_t k_op = var2op[ arg[2] ]; - op_info[k_op].usage = yes_usage; - } - break; // ----------------------------------------------------- - - // ============================================================= - // cumuilative summation operator - // ============================================================ - case CSumOp: - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 1 ); - { - size_t num_add = size_t( arg[0] ); - size_t num_sub = size_t( arg[1] ); - for(size_t i = 0; i < num_add + num_sub; i++) - { size_t j_op = var2op[ arg[3 + i] ]; - usage_cexp_parent2arg( - sum_op, i_op, j_op, op_info, cexp_set - ); - } - } - // ============================================================= - // user defined atomic operators - // ============================================================ - - case UserOp: - // start or end atomic operation sequence - if( user_state == end_user ) - { // revese_user using op_info instead of play - size_t user_index = arg[0]; - user_old = arg[1]; - user_n = arg[2]; - user_m = arg[3]; - user_j = user_n; - user_i = user_m; - user_state = ret_user; - user_atom = atomic_base::class_object(user_index); - // ------------------------------------------------------- - last_user_i_op = i_op; - CPPAD_ASSERT_UNKNOWN( i_op > user_n + user_m + 1 ); - CPPAD_ASSERT_UNKNOWN(op_info[last_user_i_op].usage==no_usage); -# ifndef NDEBUG - if( cexp_set.n_set() > 0 ) - { sparse_pack_const_iterator itr(cexp_set, last_user_i_op); - CPPAD_ASSERT_UNKNOWN( *itr == cexp_set.end() ); - } -# endif - // - user_x.resize( user_n ); - user_ix.resize( user_n ); - // - user_pack = user_atom->sparsity() == - atomic_base::pack_sparsity_enum; - user_bool = user_atom->sparsity() == - atomic_base::bool_sparsity_enum; - user_set = user_atom->sparsity() == - atomic_base::set_sparsity_enum; - CPPAD_ASSERT_UNKNOWN( user_pack || user_bool || user_set ); - // - // Note that q is one for this call the sparsity calculation - if( user_pack ) - { user_r_pack.resize( user_m ); - user_s_pack.resize( user_n ); - for(size_t i = 0; i < user_m; i++) - user_r_pack[ i ] = false; - } - if( user_bool ) - { user_r_bool.resize( user_m ); - user_s_bool.resize( user_n ); - for(size_t i = 0; i < user_m; i++) - user_r_bool[ i ] = false; - } - if( user_set ) - { user_s_set.resize(user_n); - user_r_set.resize(user_m); - for(size_t i = 0; i < user_m; i++) - user_r_set[i].clear(); - } - } - else - { // reverse_user using op_info instead of play - CPPAD_ASSERT_UNKNOWN( user_state == start_user ); - CPPAD_ASSERT_UNKNOWN( user_n == size_t(arg[2]) ); - CPPAD_ASSERT_UNKNOWN( user_m == size_t(arg[3]) ); - CPPAD_ASSERT_UNKNOWN( user_j == 0 ); - CPPAD_ASSERT_UNKNOWN( user_i == 0 ); - user_state = end_user; - // ------------------------------------------------------- - CPPAD_ASSERT_UNKNOWN( - i_op + user_n + user_m + 1 == last_user_i_op - ); - // call users function for this operation - user_atom->set_old(user_old); - bool user_ok = false; - size_t user_q = 1; // as if sum of dependent variables - if( user_pack ) - { user_ok = user_atom->rev_sparse_jac( - user_q, user_r_pack, user_s_pack, user_x - ); - if( ! user_ok ) user_ok = user_atom->rev_sparse_jac( - user_q, user_r_pack, user_s_pack - ); - } - if( user_bool ) - { user_ok = user_atom->rev_sparse_jac( - user_q, user_r_bool, user_s_bool, user_x - ); - if( ! user_ok ) user_ok = user_atom->rev_sparse_jac( - user_q, user_r_bool, user_s_bool - ); - } - if( user_set ) - { user_ok = user_atom->rev_sparse_jac( - user_q, user_r_set, user_s_set, user_x - ); - if( ! user_ok ) user_ok = user_atom->rev_sparse_jac( - user_q, user_r_set, user_s_set - ); - } - if( ! user_ok ) - { std::string s = - "Optimizing an ADFun object" - " that contains the atomic function\n\t"; - s += user_atom->afun_name(); - s += "\nCurrent atomic_sparsity is set to "; - // - if( user_set ) - s += "set_sparsity_enum.\n"; - if( user_bool ) - s += "bool_sparsity_enum.\n"; - if( user_pack ) - s += "pack_sparsity_enum.\n"; - // - s += "This version of rev_sparse_jac returned false"; - CPPAD_ASSERT_KNOWN(false, s.c_str() ); - } - - if( op_info[last_user_i_op].usage != no_usage ) - for(size_t j = 0; j < user_n; j++) - if( user_ix[j] > 0 ) - { // This user argument is a variable - bool use_arg_j = false; - if( user_set ) - { if( ! user_s_set[j].empty() ) - use_arg_j = true; - } - if( user_bool ) - { if( user_s_bool[j] ) - use_arg_j = true; - } - if( user_pack ) - { if( user_s_pack[j] ) - use_arg_j = true; - } - if( use_arg_j ) - { size_t j_op = var2op[ user_ix[j] ]; - usage_cexp_parent2arg( - sum_op, last_user_i_op, j_op, op_info, cexp_set - ); - } - } - // copy set infomation from last to first - if( cexp_set.n_set() > 0 ) - cexp_set.assignment(i_op, last_user_i_op, cexp_set); - // copy user information from last to all the user operators - // for this call - for(size_t j = 0; j < user_n + user_m + 1; ++j) - op_info[i_op + j].usage = op_info[last_user_i_op].usage; - } - break; // ------------------------------------------------------- - - case UsrapOp: - // parameter argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - // - // reverse_user using op_info instead of play - CPPAD_ASSERT_NARG_NRES(op, 1, 0); - CPPAD_ASSERT_UNKNOWN( 0 < user_j && user_j < user_n ); - --user_j; - if( user_j == 0 ) - user_state = start_user; - // ------------------------------------------------------------- - user_ix[user_j] = 0; - // - // parameter arguments - user_x[user_j] = parameter[arg[0]]; - // - break; - - case UsravOp: - // variable argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( arg[0] <= op_info[i_op].i_var ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - // - // reverse_user using op_info instead of play - CPPAD_ASSERT_NARG_NRES(op, 1, 0); - CPPAD_ASSERT_UNKNOWN( 0 < user_j && user_j <= user_n ); - --user_j; - if( user_j == 0 ) - user_state = start_user; - // ------------------------------------------------------------- - user_ix[user_j] = arg[0]; - // - // variable arguments as parameters - user_x[user_j] = CppAD::numeric_limits::quiet_NaN(); - // - break; - - case UsrrvOp: - // variable result in an atomic operation sequence - // - // reverse_user using op_info instead of play - CPPAD_ASSERT_NARG_NRES(op, 0, 1); - CPPAD_ASSERT_UNKNOWN( 0 < user_i && user_i <= user_m ); - --user_i; - if( user_i == 0 ) - user_state = arg_user; - // ------------------------------------------------------------- - if( use_result ) - { if( user_set ) - user_r_set[user_i].insert(0); - if( user_bool ) - user_r_bool[user_i] = true; - if( user_pack ) - user_r_pack[user_i] = true; - // - usage_cexp_parent2arg( - sum_op, i_op, last_user_i_op, op_info, cexp_set - ); - } - break; // -------------------------------------------------------- - - case UsrrpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - // - // reverse_user using op_info instead of play - CPPAD_ASSERT_NARG_NRES(op, 0, 1); - CPPAD_ASSERT_UNKNOWN( 0 < user_i && user_i < user_m ); - --user_i; - if( user_i == 0 ) - user_state = arg_user; - break; - // ============================================================ - - // all cases should be handled above - default: - CPPAD_ASSERT_UNKNOWN(0); - } - } - // ---------------------------------------------------------------------- - // compute previous in op_info - // ---------------------------------------------------------------------- - sparse_list hash_table_op; - hash_table_op.resize(CPPAD_HASH_TABLE_SIZE, num_op); - // - user_state = start_user; - for(i_op = 0; i_op < num_op; ++i_op) - { op_info[i_op].previous = 0; - - if( op_info[i_op].usage == yes_usage ) switch( op_info[i_op].op ) - { - case NumberOp: - CPPAD_ASSERT_UNKNOWN(false); - break; - - case BeginOp: - case CExpOp: - case CSkipOp: - case CSumOp: - case EndOp: - case InvOp: - case LdpOp: - case LdvOp: - case ParOp: - case PriOp: - case StppOp: - case StpvOp: - case StvpOp: - case StvvOp: - case UserOp: - case UsrapOp: - case UsravOp: - case UsrrpOp: - case UsrrvOp: - // these operators never match pevious operators - break; - - case AbsOp: - case AcosOp: - case AcoshOp: - case AddpvOp: - case AddvvOp: - case AsinOp: - case AsinhOp: - case AtanOp: - case AtanhOp: - case CosOp: - case CoshOp: - case DisOp: - case DivpvOp: - case DivvpOp: - case DivvvOp: - case EqpvOp: - case EqvvOp: - case ErfOp: - case ExpOp: - case Expm1Op: - case LepvOp: - case LevpOp: - case LevvOp: - case LogOp: - case Log1pOp: - case LtpvOp: - case LtvpOp: - case LtvvOp: - case MulpvOp: - case MulvvOp: - case NepvOp: - case NevvOp: - case PowpvOp: - case PowvpOp: - case PowvvOp: - case SignOp: - case SinOp: - case SinhOp: - case SqrtOp: - case SubpvOp: - case SubvpOp: - case SubvvOp: - case TanOp: - case TanhOp: - case ZmulpvOp: - case ZmulvpOp: - case ZmulvvOp: - // check for a previous match - match_op( var2op, op_info, i_op, hash_table_op ); - if( op_info[i_op].previous != 0 ) - { // like a unary operator that assigns i_op equal to previous. - size_t previous = op_info[i_op].previous; - bool sum_op = false; - CPPAD_ASSERT_UNKNOWN( previous < i_op ); - usage_cexp_parent2arg( - sum_op, i_op, previous, op_info, cexp_set - ); - } - break; - } - } - // ---------------------------------------------------------------------- - // compute cskip_info - // ---------------------------------------------------------------------- - if( cexp_set.n_set() == 0 ) - return; - // - // initialize information for each conditional expression - cskip_info.resize(num_cexp_op); - for(size_t i = 0; i < num_cexp_op; i++) - { CPPAD_ASSERT_UNKNOWN( - op_info[i].previous == 0 || op_info[i].usage == yes_usage - ); - i_op = cexp2op[i]; - arg = op_info[i_op].arg; - CPPAD_ASSERT_UNKNOWN( op_info[i_op].op == CExpOp ); - // - struct_cskip_info info; - info.i_op = i_op; - info.cop = CompareOp( arg[0] ); - info.flag = arg[1]; - info.left = arg[2]; - info.right = arg[3]; - // - // max_left_right - size_t index = 0; - if( arg[1] & 1 ) - index = std::max(index, info.left); - if( arg[1] & 2 ) - index = std::max(index, info.right); - CPPAD_ASSERT_UNKNOWN( index > 0 ); - info.max_left_right = index; - // - cskip_info[i] = info; - }; - // Determine which operators can be conditionally skipped - i_op = 0; - while(i_op < num_op) - { size_t j_op = i_op; - bool keep = op_info[i_op].usage != no_usage; - keep &= op_info[i_op].usage != csum_usage; - keep &= op_info[i_op].previous == 0; - if( keep ) - { sparse_pack_const_iterator itr(cexp_set, i_op); - if( *itr != cexp_set.end() ) - { if( op_info[i_op].op == UserOp ) - { // i_op is the first operations in this user atomic call. - // Find the last operation in this call. - ++j_op; - while( op_info[j_op].op != UserOp ) - { switch( op_info[j_op].op ) - { case UsrapOp: - case UsravOp: - case UsrrpOp: - case UsrrvOp: - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } - ++j_op; - } - } - } - while( *itr != cexp_set.end() ) - { size_t element = *itr; - size_t index = element / 2; - bool compare = bool( element % 2 ); - if( compare == false ) - { cskip_info[index].skip_op_false.push_back(i_op); - if( j_op != i_op ) - cskip_info[index].skip_op_false.push_back(j_op); - } - else - { cskip_info[index].skip_op_true.push_back(i_op); - if( j_op != i_op ) - cskip_info[index].skip_op_true.push_back(j_op); - } - ++itr; - } - } - CPPAD_ASSERT_UNKNOWN( i_op <= j_op ); - i_op += (1 + j_op) - i_op; - } - return; -} - -} } } // END_CPPAD_LOCAL_OPTIMIZE_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize/hash_code.hpp b/ct_core/include/ct/external/cppad/local/optimize/hash_code.hpp deleted file mode 100644 index 8d9ef79c2..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize/hash_code.hpp +++ /dev/null @@ -1,58 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_OPTIMIZE_HASH_CODE_HPP -# define CPPAD_LOCAL_OPTIMIZE_HASH_CODE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/*! -\file local/optimize/hash_code.hpp -CppAD hashing utility. -*/ - - -// BEGIN_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -namespace CppAD { namespace local { namespace optimize { -/*! -Specialized hash code for a CppAD operator and its arguments -(used during optimization). - -\param op -is the operator that we are computing a hash code for. - -\param num_arg -number of elements of arg to include in the hash code -(num_arg <= 2). - -\param arg -is a vector of length num_arg -containing the corresponding argument indices for this operator. - -\return -is a hash code that is between zero and CPPAD_HASH_TABLE_SIZE - 1. -*/ - -inline size_t optimize_hash_code( - OpCode op , - size_t num_arg , - const addr_t* arg ) -{ - // - CPPAD_ASSERT_UNKNOWN(num_arg <= 2 ); - size_t sum = size_t(arg[0]) + size_t(op); - if( 1 < num_arg ) - sum += size_t(arg[1]); - // - return sum % CPPAD_HASH_TABLE_SIZE; -} - -} } } // END_CPPAD_LOCAL_OPTIMIZE_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize/match_op.hpp b/ct_core/include/ct/external/cppad/local/optimize/match_op.hpp deleted file mode 100644 index 2a0844c9b..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize/match_op.hpp +++ /dev/null @@ -1,270 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_OPTIMIZE_MATCH_OP_HPP -# define CPPAD_LOCAL_OPTIMIZE_MATCH_OP_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -/*! -\file match_op.hpp -Check if current operator matches a previous operator. -*/ -// BEGIN_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -namespace CppAD { namespace local { namespace optimize { -/*! -Search for a previous operator that matches the current one. - -If an argument for the current operator is a variable, -and the argument has previous match, -the previous match for the argument is used when checking for a match -for the current operator. - -\param var2op -mapping from variable index to operator index. - -\param op_info -Mapping from operator index to operator information. -The input value of op_info[current].previous is assumed to be zero. -If a match if found, -the output value of op_info[current].previous is set to the -matching operator index, otherwise it is left as is. -Note that op_info[current].previous < current. - -\param current -is the index of the current operator which must be an unary -or binary operator. Note that NumArg(ErfOp) == 3 but it is effectivey -a unary operator and is allowed otherwise NumArg( op_info[current].op) < 3. -It is assumed that hash_table_op is initialized as a vector of emtpy -sets. After this initialization, the value of current inceases with -each call to match_op. - -\li -This must be a unary or binary -operator; hence, NumArg( op_info[current].op ) is one or two. -There is one exception, NumRes( ErfOp ) == 3, but arg[0] -is the only true arguments (the others are always the same). - -\li -This must not be a VecAD load or store operation; i.e., -LtpvOp, LtvpOp, LtvvOp, StppOp, StpvOp, StvpOp, StvvOp. -It also must not be an independent variable operator InvOp. - -\param hash_table_op -is a vector of sets, -hash_table_op.n_set() == CPPAD_HASH_TABLE_SIZE and -hash_table_op.end() == op_info.size(). -If i_op is an element of set[j], -then the operation op_info[i_op] has hash code j, -and op_info[i_op] does not match any other element of set[j]. -An entry will be added each time match_op is called -and a match for the current operator is not found. -*/ - -inline void match_op( - const vector& var2op , - vector& op_info , - size_t current , - sparse_list& hash_table_op ) -{ size_t num_op = op_info.size(); - // - CPPAD_ASSERT_UNKNOWN( op_info[current].previous == 0 ); - CPPAD_ASSERT_UNKNOWN( - hash_table_op.n_set() == CPPAD_HASH_TABLE_SIZE - ); - CPPAD_ASSERT_UNKNOWN( hash_table_op.end() == num_op ); - CPPAD_ASSERT_UNKNOWN( current < num_op ); - // - // current operator - OpCode op = op_info[current].op; - const addr_t* arg = op_info[current].arg; - // - // which arguments are variable - size_t num_arg = NumArg(op); - // - bool variable[2]; - variable[0] = false; - variable[1] = false; - switch(op) - { // - case ErfOp: - num_arg = 1; // other arugments are always the same - // - case AbsOp: - case AcosOp: - case AcoshOp: - case AsinOp: - case AsinhOp: - case AtanOp: - case AtanhOp: - case CosOp: - case CoshOp: - case ExpOp: - case Expm1Op: - case LogOp: - case Log1pOp: - case SignOp: - case SinOp: - case SinhOp: - case SqrtOp: - case TanOp: - case TanhOp: - CPPAD_ASSERT_UNKNOWN( num_arg == 1 ); - variable[0] = true; - break; - - - case AddpvOp: - case DisOp: - case DivpvOp: - case EqpvOp: - case LepvOp: - case LtpvOp: - case MulpvOp: - case NepvOp: - case PowpvOp: - case SubpvOp: - case ZmulpvOp: - CPPAD_ASSERT_UNKNOWN( num_arg == 2 ); - variable[1] = true; - break; - - case DivvpOp: - case LevpOp: - case LtvpOp: - case PowvpOp: - case SubvpOp: - case ZmulvpOp: - CPPAD_ASSERT_UNKNOWN( num_arg == 2 ); - variable[0] = true; - break; - - case AddvvOp: - case DivvvOp: - case EqvvOp: - case LevvOp: - case LtvvOp: - case MulvvOp: - case NevvOp: - case PowvvOp: - case SubvvOp: - case ZmulvvOp: - CPPAD_ASSERT_UNKNOWN( num_arg == 2 ); - variable[0] = true; - variable[1] = true; - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } - // - // If i-th argument to current operator has a previous operator, - // this is the i-th argument for previous operator. - // Otherwise, it is the i-th argument for the current operator - // (if a previous variable exists) - addr_t arg_match[2]; - for(size_t j = 0; j < num_arg; ++j) - { arg_match[j] = arg[j]; - if( variable[j] ) - { size_t previous = op_info[ var2op[arg[j]] ].previous; - if( previous != 0 ) - { CPPAD_ASSERT_UNKNOWN( op_info[previous].previous == 0 ); - // - arg_match[j] = op_info[previous].i_var; - } - } - } - unsigned short code = optimize_hash_code(op, num_arg, arg_match); - // - // iterator for the set with this hash code - sparse_list_const_iterator itr(hash_table_op, code); - // - // check for a match - size_t count = 0; - while( *itr != num_op ) - { ++count; - // - // candidate previous for current operator - size_t candidate = *itr; - CPPAD_ASSERT_UNKNOWN( candidate < current ); - CPPAD_ASSERT_UNKNOWN( op_info[candidate].previous == 0 ); - // - // check for a match - bool match = op == op_info[candidate].op; - if( match ) - { for(size_t j = 0; j < num_arg; j++) - { if( variable[j] ) - { size_t previous = - op_info[ var2op[op_info[candidate].arg[j]] ].previous; - if( previous != 0 ) - { CPPAD_ASSERT_UNKNOWN(op_info[previous].previous == 0); - // - match &= - arg_match[j] == addr_t( op_info[previous].i_var ); - } - else - match &= arg_match[j] == op_info[candidate].arg[j]; - } - } - } - if( match ) - { op_info[current].previous = candidate; - return; - } - ++itr; - } - - // special case where operator is commutative - if( (op == AddvvOp) | (op == MulvvOp ) ) - { CPPAD_ASSERT_UNKNOWN( NumArg(op) == 2 ); - std::swap( arg_match[0], arg_match[1] ); - // - code = optimize_hash_code(op, num_arg, arg_match); - sparse_list_const_iterator itr_swap(hash_table_op, code); - while( *itr_swap != num_op ) - { - size_t candidate = *itr_swap; - CPPAD_ASSERT_UNKNOWN( candidate < current ); - CPPAD_ASSERT_UNKNOWN( op_info[candidate].previous == 0 ); - // - bool match = op == op_info[candidate].op; - if( match ) - { for(size_t j = 0; j < num_arg; j++) - { CPPAD_ASSERT_UNKNOWN( variable[j] ) - size_t previous = - op_info[ var2op[op_info[candidate].arg[j]] ].previous; - if( previous != 0 ) - { CPPAD_ASSERT_UNKNOWN(op_info[previous].previous == 0); - // - match &= - arg_match[j] == addr_t( op_info[previous].i_var ); - } - else - match &= arg_match[j] == op_info[candidate].arg[j]; - } - } - if( match ) - { op_info[current].previous = candidate; - return; - } - ++itr_swap; - } - } - CPPAD_ASSERT_UNKNOWN( count < 11 ); - if( count == 10 ) - { // restart the list - hash_table_op.clear(code); - } - // no match was found, add this operator the the set for this hash code - hash_table_op.add_element(code, current); -} - -} } } // END_CPPAD_LOCAL_OPTIMIZE_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize/old2new.hpp b/ct_core/include/ct/external/cppad/local/optimize/old2new.hpp deleted file mode 100644 index 850f84869..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize/old2new.hpp +++ /dev/null @@ -1,34 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_OPTIMIZE_OLD2NEW_HPP -# define CPPAD_LOCAL_OPTIMIZE_OLD2NEW_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/*! -\file old2new.hpp -Information that maps old an old operator to a new opeator and new variable. -*/ - -// BEGIN_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -namespace CppAD { namespace local { namespace optimize { -/*! -Information that maps old an old operator to a new opeator and new variable. -*/ -struct struct_old2new { - /// New operator index for this old operator. - addr_t new_op; - - /// New varaible index for this old operator. - addr_t new_var; -}; - -} } } // END_CPPAD_LOCAL_OPTIMIZE_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize/op_info.hpp b/ct_core/include/ct/external/cppad/local/optimize/op_info.hpp deleted file mode 100644 index 45820e9a3..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize/op_info.hpp +++ /dev/null @@ -1,51 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_OPTIMIZE_OP_INFO_HPP -# define CPPAD_LOCAL_OPTIMIZE_OP_INFO_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include -# include - -// BEGIN_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -namespace CppAD { namespace local { namespace optimize { - -/// information for one operator -struct struct_op_info { - /// arguments - const addr_t* arg; - - /// Primary (not auxillary) variable index for this operator. If the - // operator has not results, this is num_var (an invalid variable index). - addr_t i_var; - - /*! - previous operator that can be used in place of this operator. - \li - If previous == 0, no such operator was found. - \li - If previous != 0, - op_info[pevious].previous == 0 and - op_info[previous].usage == yes_usage. - */ - addr_t previous; - - /// op code - OpCode op; - - /// How is this operator used to compute the dependent variables. - /// If usage = csum_usage or usage = no_usage, previous = 0. - enum_usage usage; - -}; - -} } } // END_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize/optimize_run.hpp b/ct_core/include/ct/external/cppad/local/optimize/optimize_run.hpp deleted file mode 100644 index 877ed0988..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize/optimize_run.hpp +++ /dev/null @@ -1,884 +0,0 @@ -// $Id$ - -# ifndef CPPAD_LOCAL_OPTIMIZE_OPTIMIZE_RUN_HPP -# define CPPAD_LOCAL_OPTIMIZE_OPTIMIZE_RUN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include - -/*! -\file optimize_run.hpp -Convert a player object to an optimized recorder object -*/ -// BEGIN_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -namespace CppAD { namespace local { namespace optimize { -/*! -Convert a player object to an optimized recorder object - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - - -\param options -\li -If the sub-string "no_conditional_skip" appears, -conditional skip operations will not be generated. -This may make the optimize routine use significantly less memory -and take significantly less time. -\li -If the sub-string "no_compare_op" appears, -then comparison operators will be removed from the optimized tape. -These operators are necessary for the compare_change function to be -be meaningful in the resulting recording. -On the other hand, they are not necessary and take extra time -when compare_change is not used. -\li -If the sub-string "no_print_for" appears, -then print forward (PriOp) operators will be removed from the optimized tape. -These operators are useful for reporting problems evaluating derivatives -at independent variable values different from those used to record a function. - -\param n -is the number of independent variables on the tape. - -\param dep_taddr -On input this vector contains the indices for each of the dependent -variable values in the operation sequence corresponding to \a play. -Upon return it contains the indices for the same variables but in -the operation sequence corresponding to \a rec. - -\param play -This is the operation sequence that we are optimizing. -It is essentially const, except for play back state which -changes while it plays back the operation seqeunce. - -\param rec -The input contents of this recording does not matter. -Upon return, it contains an optimized verison of the -operation sequence corresponding to \a play. -*/ - -template -void optimize_run( - const std::string& options , - size_t n , - CppAD::vector& dep_taddr , - player* play , - recorder* rec ) -{ - bool conditional_skip = true; - bool compare_op = true; - bool print_for_op = true; - size_t index = 0; - while( index < options.size() ) - { while( index < options.size() && options[index] == ' ' ) - ++index; - std::string option; - while( index < options.size() && options[index] != ' ' ) - option += options[index++]; - if( option != "" ) - { if( option == "no_conditional_skip" ) - conditional_skip = false; - else if( option == "no_compare_op" ) - compare_op = false; - else if( option == "no_print_for_op" ) - print_for_op = false; - else - { option += " is not a valid optimize option"; - CPPAD_ASSERT_KNOWN( false , option.c_str() ); - } - } - } - // number of operators in the player - const size_t num_op = play->num_op_rec(); - CPPAD_ASSERT_UNKNOWN( - num_op < size_t( std::numeric_limits::max() ) - ); - - // number of variables in the player - const size_t num_var = play->num_var_rec(); - - // number of VecAD indices - size_t num_vecad_ind = play->num_vec_ind_rec(); - - // number of VecAD vectors - size_t num_vecad_vec = play->num_vecad_vec_rec(); - - // operator information - vector var2op; - vector cskip_info; - vector vecad_used; - vector op_info; - get_op_info( - conditional_skip, - compare_op, - print_for_op, - play, - dep_taddr, - var2op, - cskip_info, - vecad_used, - op_info - ); - - // nan with type Base - Base base_nan = Base( std::numeric_limits::quiet_NaN() ); - - // ------------------------------------------------------------- - // information for current operator - size_t i_op; // index - OpCode op; // operator - const addr_t* arg; // arguments - size_t i_var; // variable index of primary (last) result - - enum_user_state user_state; - // ------------------------------------------------------------- - // conditional skip information - // - // size of the conditional cskip information structure - // (This is equal to the number of conditional expressions when - // conditional_skip is true.) - size_t num_cskip = cskip_info.size(); - CPPAD_ASSERT_UNKNOWN( conditional_skip || num_cskip == 0 ); - - // sort the conditional skip information by max_left_right - vector cskip_info_order(num_cskip); - if( num_cskip > 0 ) - { CppAD::vector keys(num_cskip); - for(size_t i = 0; i < num_cskip; i++) - keys[i] = cskip_info[i].max_left_right; - CppAD::index_sort(keys, cskip_info_order); - } - - // index in sorted order - size_t cskip_order_next = 0; - - // index in order during reverse sweep - size_t cskip_info_index = num_cskip; - vector cskip_new(num_cskip); - // flag used to indicate that this conditional expression is skipped - for(size_t i = 0; i < num_cskip; i++) - cskip_new[i].i_arg = 0; - // ------------------------------------------------------------- - - // Erase all information in the old recording - rec->free(); - - // initialize mapping from old VecAD index to new VecAD index - CppAD::vector new_vecad_ind(num_vecad_ind); - for(size_t i = 0; i < num_vecad_ind; i++) - new_vecad_ind[i] = num_vecad_ind; // invalid index - { - size_t j = 0; // index into the old set of indices - for(size_t i = 0; i < num_vecad_vec; i++) - { // length of this VecAD - size_t length = play->GetVecInd(j); - if( vecad_used[i] ) - { // Put this VecAD vector in new recording - CPPAD_ASSERT_UNKNOWN(length < num_vecad_ind); - new_vecad_ind[j] = rec->PutVecInd(length); - for(size_t k = 1; k <= length; k++) new_vecad_ind[j+k] = - rec->PutVecInd( - rec->PutPar( - play->GetPar( - play->GetVecInd(j+k) - ) ) ); - } - // start of next VecAD - j += length + 1; - } - CPPAD_ASSERT_UNKNOWN( j == num_vecad_ind ); - } - // - // Mapping from old operator index to new operator information - // (zero is invalid except for old2new[0].new_op and old2new[0].i_var) - vector old2new(num_op); - for(size_t i = 0; i < num_op; i++) - { old2new[i].new_op = 0; - old2new[i].new_var = 0; - } - - - // temporary buffer for new argument values - addr_t new_arg[6]; - - // temporary work space used by record_csum - // (decalared here to avoid realloaction of memory) - struct_csum_stacks csum_work; - - // tempory used to hold a size_pair - struct_size_pair size_pair; - - user_state = start_user; - for(i_op = 0; i_op < num_op; ++i_op) - { addr_t mask; // temporary used in some switch cases - // - // this operator information - op = op_info[i_op].op; - arg = op_info[i_op].arg; - i_var = op_info[i_op].i_var; - // - // determine if we should insert a conditional skip here - bool skip = conditional_skip; - skip &= cskip_order_next < num_cskip; - skip &= op != BeginOp; - skip &= op != InvOp; - skip &= user_state == start_user; - if( skip ) - { size_t j = cskip_info_order[cskip_order_next]; - if( NumRes(op) > 0 ) - skip &= cskip_info[j].max_left_right < i_var; - else - skip &= cskip_info[j].max_left_right <= i_var; - } - if( skip ) - { size_t j = cskip_info_order[cskip_order_next]; - cskip_order_next++; - struct_cskip_info info = cskip_info[j]; - size_t n_true = info.skip_op_true.size(); - size_t n_false = info.skip_op_false.size(); - skip &= n_true > 0 || n_false > 0; - if( skip ) - { CPPAD_ASSERT_UNKNOWN( NumRes(CSkipOp) == 0 ); - size_t n_arg = 7 + n_true + n_false; - // reserve space for the arguments to this operator but - // delay setting them until we have all the new addresses - cskip_new[j].i_arg = rec->ReserveArg(n_arg); - // i_arg == 0 is used to check if conditional expression - // has been skipped. - CPPAD_ASSERT_UNKNOWN( cskip_new[j].i_arg > 0 ); - // There is no corresponding old operator in this case - rec->PutOp(CSkipOp); - } - } - if( op == UserOp ) - { if( user_state == start_user ) - user_state = end_user; - else - { CPPAD_ASSERT_UNKNOWN( user_state == end_user ); - user_state = start_user; - } - } - size_t previous; - // - if( op_info[i_op].usage == yes_usage ) switch( op ) - { - case BeginOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - // Put BeginOp at beginning of recording - old2new[i_op].new_op = rec->num_op_rec(); - old2new[i_op].new_var = rec->PutOp(BeginOp); - rec->PutArg(arg[0]); - break; - - // -------------------------------------------------------------- - // Unary operator where operand is arg[0] - case AbsOp: - case AcosOp: - case AcoshOp: - case AsinOp: - case AsinhOp: - case AtanOp: - case AtanhOp: - case CosOp: - case CoshOp: - case ErfOp: - case ExpOp: - case Expm1Op: - case LogOp: - case Log1pOp: - case SignOp: - case SinOp: - case SinhOp: - case SqrtOp: - case TanOp: - case TanhOp: - previous = op_info[i_op].previous; - if( previous > 0 ) - { size_t j_op = previous; - old2new[i_op].new_var = old2new[j_op].new_var; - } - else - { // - new_arg[0] = old2new[ var2op[arg[0]] ].new_var; - rec->PutArg( new_arg[0] ); - // - old2new[i_op].new_op = rec->num_op_rec(); - old2new[i_op].new_var = rec->PutOp(op); - CPPAD_ASSERT_UNKNOWN( - new_arg[0] < old2new[var2op[i_var]].new_var - ); - if( op == ErfOp ) - { // Error function is a special case - // second argument is always the parameter 0 - // third argument is always the parameter 2 / sqrt(pi) - CPPAD_ASSERT_UNKNOWN( NumArg(ErfOp) == 3 ); - rec->PutArg( rec->PutPar( Base(0) ) ); - rec->PutArg( rec->PutPar( - Base( 1.0 / std::sqrt( std::atan(1.0) ) ) - ) ); - } - } - break; - // --------------------------------------------------- - // Binary operators where - // left is a variable and right is a parameter - case SubvpOp: - // check if this is the top of a csum connection - if( op_info[i_op].usage == csum_usage ) - break; - if( op_info[ var2op[arg[0]] ].usage == csum_usage ) - { - // convert to a sequence of summation operators - size_pair = record_csum( - var2op , - op_info , - old2new , - i_var , - play->num_par_rec() , - play->GetPar() , - rec , - csum_work - ); - old2new[i_op].new_op = size_pair.i_op; - old2new[i_op].new_var = size_pair.i_var; - // abort rest of this case - break; - } - case DivvpOp: - case PowvpOp: - case ZmulvpOp: - previous = op_info[i_op].previous; - if( previous > 0 ) - { size_t j_op = previous; - old2new[i_op].new_var = old2new[j_op].new_var; - } - else - { // - size_pair = record_vp( - var2op , - op_info , - old2new , - i_var , - play->num_par_rec() , - play->GetPar() , - rec , - op , - arg - ); - old2new[i_op].new_op = size_pair.i_op; - old2new[i_op].new_var = size_pair.i_var; - } - break; - // --------------------------------------------------- - // Binary operators where - // left is an index and right is a variable - case DisOp: - previous = op_info[i_op].previous; - if( previous > 0 ) - { size_t j_op = previous; - old2new[i_op].new_var = old2new[j_op].new_var; - } - else - { // - new_arg[0] = arg[0]; - new_arg[1] = old2new[ var2op[arg[1]] ].new_var; - rec->PutArg( new_arg[0], new_arg[1] ); - // - old2new[i_op].new_op = rec->num_op_rec(); - old2new[i_op].new_var = rec->PutOp(op); - CPPAD_ASSERT_UNKNOWN( - new_arg[1] < old2new[var2op[i_var]].new_var - ); - } - break; - - // --------------------------------------------------- - // Binary operators where - // left is a parameter and right is a variable - case SubpvOp: - case AddpvOp: - // check if this is the top of a csum connection - if( op_info[i_op].usage == csum_usage ) - break; - if( op_info[ var2op[arg[1]] ].usage == csum_usage ) - { - // convert to a sequence of summation operators - size_pair = record_csum( - var2op , - op_info , - old2new , - i_var , - play->num_par_rec() , - play->GetPar() , - rec , - csum_work - ); - old2new[i_op].new_op = size_pair.i_op; - old2new[i_op].new_var = size_pair.i_var; - // abort rest of this case - break; - } - case DivpvOp: - case MulpvOp: - case PowpvOp: - case ZmulpvOp: - previous = op_info[i_op].previous; - if( previous > 0 ) - { size_t j_op = previous; - old2new[i_op].new_var = old2new[j_op].new_var; - } - else - { // - size_pair = record_pv( - var2op , - op_info , - old2new , - i_var , - play->num_par_rec() , - play->GetPar() , - rec , - op , - arg - ); - old2new[i_op].new_op = size_pair.i_op; - old2new[i_op].new_var = size_pair.i_var; - } - break; - // --------------------------------------------------- - // Binary operator where both operands are variables - case AddvvOp: - case SubvvOp: - // check if this is the top of a csum connection - if( op_info[i_op].usage == csum_usage ) - break; - if( - op_info[ var2op[arg[0]] ].usage == csum_usage || - op_info[ var2op[arg[1]] ].usage == csum_usage - ) - { - // convert to a sequence of summation operators - size_pair = record_csum( - var2op , - op_info , - old2new , - i_var , - play->num_par_rec() , - play->GetPar() , - rec , - csum_work - ); - old2new[i_op].new_op = size_pair.i_op; - old2new[i_op].new_var = size_pair.i_var; - // abort rest of this case - break; - } - case DivvvOp: - case MulvvOp: - case PowvvOp: - case ZmulvvOp: - previous = op_info[i_op].previous; - if( previous > 0 ) - { size_t j_op = previous; - old2new[i_op].new_var = old2new[j_op].new_var; - } - else - { // - size_pair = record_vv( - var2op , - op_info , - old2new , - i_var , - play->num_par_rec() , - play->GetPar() , - rec , - op , - arg - ); - old2new[i_op].new_op = size_pair.i_op; - old2new[i_op].new_var = size_pair.i_var; - } - break; - // --------------------------------------------------- - // Conditional expression operators - case CExpOp: - CPPAD_ASSERT_NARG_NRES(op, 6, 1); - new_arg[0] = arg[0]; - new_arg[1] = arg[1]; - mask = 1; - for(size_t i = 2; i < 6; i++) - { if( arg[1] & mask ) - { new_arg[i] = old2new[ var2op[arg[i]] ].new_var; - CPPAD_ASSERT_UNKNOWN( - size_t(new_arg[i]) < num_var - ); - } - else new_arg[i] = rec->PutPar( - play->GetPar( arg[i] ) - ); - mask = mask << 1; - } - rec->PutArg( - new_arg[0] , - new_arg[1] , - new_arg[2] , - new_arg[3] , - new_arg[4] , - new_arg[5] - ); - old2new[i_op].new_op = rec->num_op_rec(); - old2new[i_op].new_var = rec->PutOp(op); - // - // The new addresses for left and right are used during - // fill in the arguments for the CSkip operations. This does not - // affect max_left_right which is used during this sweep. - if( conditional_skip ) - { CPPAD_ASSERT_UNKNOWN( cskip_info_index > 0 ); - cskip_info_index--; - cskip_new[ cskip_info_index ].left = new_arg[2]; - cskip_new[ cskip_info_index ].right = new_arg[3]; - } - break; - // --------------------------------------------------- - // Operations with no arguments and no results - case EndOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 0); - old2new[i_op].new_op = rec->num_op_rec(); - rec->PutOp(op); - break; - // --------------------------------------------------- - // Operations with two arguments and no results - case LepvOp: - case LtpvOp: - case EqpvOp: - case NepvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 0); - new_arg[0] = rec->PutPar( play->GetPar(arg[0]) ); - new_arg[1] = old2new[ var2op[arg[1]] ].new_var; - rec->PutArg(new_arg[0], new_arg[1]); - old2new[i_op].new_op = rec->num_op_rec(); - rec->PutOp(op); - break; - // - case LevpOp: - case LtvpOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 0); - new_arg[0] = old2new[ var2op[arg[0]] ].new_var; - new_arg[1] = rec->PutPar( play->GetPar(arg[1]) ); - rec->PutArg(new_arg[0], new_arg[1]); - old2new[i_op].new_op = rec->num_op_rec(); - rec->PutOp(op); - break; - // - case LevvOp: - case LtvvOp: - case EqvvOp: - case NevvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 0); - new_arg[0] = old2new[ var2op[arg[0]] ].new_var; - new_arg[1] = old2new[ var2op[arg[1]] ].new_var; - rec->PutArg(new_arg[0], new_arg[1]); - old2new[i_op].new_op = rec->num_op_rec(); - rec->PutOp(op); - break; - - // --------------------------------------------------- - // Operations with no arguments and one result - case InvOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 1); - old2new[i_op].new_op = rec->num_op_rec(); - old2new[i_op].new_var = rec->PutOp(op); - break; - // --------------------------------------------------- - // Operations with one argument that is a parameter - case ParOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - new_arg[0] = rec->PutPar( play->GetPar(arg[0] ) ); - rec->PutArg( new_arg[0] ); - // - old2new[i_op].new_op = rec->num_op_rec(); - old2new[i_op].new_var = rec->PutOp(op); - break; - - // --------------------------------------------------- - // print forward operator - case PriOp: - CPPAD_ASSERT_NARG_NRES(op, 5, 0); - // arg[0] - new_arg[0] = arg[0]; - // - // arg[1] - if( arg[0] & 1 ) - { new_arg[1] = old2new[ var2op[arg[1]] ].new_var; - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[1]) < num_var ); - } - else - { new_arg[1] = rec->PutPar( play->GetPar( arg[1] ) ); - } - // - // arg[3] - if( arg[0] & 2 ) - { new_arg[3] = old2new[ var2op[arg[3]] ].new_var; - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[3]) < num_var ); - } - else - { new_arg[3] = rec->PutPar( play->GetPar( arg[3] ) ); - } - new_arg[2] = rec->PutTxt( play->GetTxt(arg[2]) ); - new_arg[4] = rec->PutTxt( play->GetTxt(arg[4]) ); - // - rec->PutArg( - new_arg[0] , - new_arg[1] , - new_arg[2] , - new_arg[3] , - new_arg[4] - ); - // new operator - old2new[i_op].new_op = rec->num_op_rec(); - // no new variable - rec->PutOp(op); - break; - - // --------------------------------------------------- - // VecAD operators - - // Load using a parameter index - case LdpOp: - CPPAD_ASSERT_NARG_NRES(op, 3, 1); - new_arg[0] = new_vecad_ind[ arg[0] ]; - new_arg[1] = arg[1]; - new_arg[2] = rec->num_load_op_rec(); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < num_vecad_ind ); - rec->PutArg( - new_arg[0], - new_arg[1], - new_arg[2] - ); - old2new[i_op].new_op = rec->num_op_rec(); - old2new[i_op].new_var = rec->PutLoadOp(op); - break; - - // Load using a variable index - case LdvOp: - CPPAD_ASSERT_NARG_NRES(op, 3, 1); - new_arg[0] = new_vecad_ind[ arg[0] ]; - new_arg[1] = old2new[ var2op[arg[1]] ].new_var; - new_arg[2] = rec->num_load_op_rec(); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < num_vecad_ind ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[1]) < num_var ); - rec->PutArg( - new_arg[0], - new_arg[1], - new_arg[2] - ); - old2new[i_op].new_op = rec->num_op_rec(); - old2new[i_op].new_var = rec->PutLoadOp(op); - break; - - // Store a parameter using a parameter index - case StppOp: - CPPAD_ASSERT_NARG_NRES(op, 3, 0); - new_arg[0] = new_vecad_ind[ arg[0] ]; - new_arg[1] = rec->PutPar( play->GetPar(arg[1]) ); - new_arg[2] = rec->PutPar( play->GetPar(arg[2]) ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < num_vecad_ind ); - rec->PutArg( - new_arg[0], - new_arg[1], - new_arg[2] - ); - old2new[i_op].new_op = rec->num_op_rec(); - rec->PutOp(op); - break; - - // Store a parameter using a variable index - case StvpOp: - CPPAD_ASSERT_NARG_NRES(op, 3, 0); - new_arg[0] = new_vecad_ind[ arg[0] ]; - new_arg[1] = old2new[ var2op[arg[1]] ].new_var; - new_arg[2] = rec->PutPar( play->GetPar(arg[2]) ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < num_vecad_ind ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[1]) < num_var ); - rec->PutArg( - new_arg[0], - new_arg[1], - new_arg[2] - ); - old2new[i_op].new_op = rec->num_op_rec(); - rec->PutOp(op); - break; - - // Store a variable using a parameter index - case StpvOp: - CPPAD_ASSERT_NARG_NRES(op, 3, 0); - new_arg[0] = new_vecad_ind[ arg[0] ]; - new_arg[1] = rec->PutPar( play->GetPar(arg[1]) ); - new_arg[2] = old2new[ var2op[arg[2]] ].new_var; - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < num_vecad_ind ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[1]) < num_var ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[2]) < num_var ); - rec->PutArg( - new_arg[0], - new_arg[1], - new_arg[2] - ); - old2new[i_op].new_op = rec->num_op_rec(); - rec->PutOp(op); - break; - - // Store a variable using a variable index - case StvvOp: - CPPAD_ASSERT_NARG_NRES(op, 3, 0); - new_arg[0] = new_vecad_ind[ arg[0] ]; - new_arg[1] = old2new[ var2op[arg[1]] ].new_var; - new_arg[2] = old2new[ var2op[arg[2]] ].new_var; - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[0]) < num_vecad_ind ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[1]) < num_var ); - CPPAD_ASSERT_UNKNOWN( size_t(new_arg[2]) < num_var ); - rec->PutArg( - new_arg[0], - new_arg[1], - new_arg[2] - ); - old2new[i_op].new_op = rec->num_op_rec(); - rec->PutOp(op); - break; - - // ----------------------------------------------------------- - // user atomic function call operators - - case UserOp: - CPPAD_ASSERT_NARG_NRES(op, 4, 0); - // user_old, user_n, user_m - rec->PutArg(arg[0], arg[1], arg[2], arg[3]); - old2new[i_op].new_op = rec->num_op_rec(); - rec->PutOp(UserOp); - break; - - case UsrapOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 0); - new_arg[0] = rec->PutPar( play->GetPar(arg[0]) ); - rec->PutArg(new_arg[0]); - old2new[i_op].new_op = rec->num_op_rec(); - rec->PutOp(UsrapOp); - break; - - case UsravOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 0); - new_arg[0] = old2new[ var2op[arg[0]] ].new_var; - if( size_t(new_arg[0]) < num_var ) - { rec->PutArg(new_arg[0]); - old2new[i_op].new_op = rec->num_op_rec(); - rec->PutOp(UsravOp); - } - else - { // This argument does not affect the result and - // has been optimized out so use nan in its place. - new_arg[0] = rec->PutPar( base_nan ); - rec->PutArg(new_arg[0]); - old2new[i_op].new_op = rec->num_op_rec(); - rec->PutOp(UsrapOp); - } - break; - - case UsrrpOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 0); - new_arg[0] = rec->PutPar( play->GetPar(arg[0]) ); - rec->PutArg(new_arg[0]); - old2new[i_op].new_op = rec->num_op_rec(); - rec->PutOp(UsrrpOp); - break; - - case UsrrvOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 1); - old2new[i_op].new_op = rec->num_op_rec(); - old2new[i_op].new_var = rec->PutOp(UsrrvOp); - break; - // --------------------------------------------------- - - // all cases should be handled above - default: - CPPAD_ASSERT_UNKNOWN(false); - - } - } - // modify the dependent variable vector to new indices - for(size_t i = 0; i < dep_taddr.size(); i++ ) - { dep_taddr[i] = old2new[ var2op[dep_taddr[i]] ].new_var; - CPPAD_ASSERT_UNKNOWN( size_t(dep_taddr[i]) < num_var ); - } - -# ifndef NDEBUG - for(i_op = 0; i_op < num_op; i_op++) - if( NumRes( op_info[i_op].op ) > 0 ) - CPPAD_ASSERT_UNKNOWN( - size_t(old2new[i_op].new_op) < rec->num_op_rec() - ); -# endif - // make sure that all the conditional expressions have been - // checked to see if they are still present - CPPAD_ASSERT_UNKNOWN( cskip_order_next == num_cskip ); - // fill in the arguments for the CSkip operations - for(size_t i = 0; i < num_cskip; i++) - { // if cskip_new[i].i_arg == 0, this conditional expression was skipped - if( cskip_new[i].i_arg > 0 ) - { struct_cskip_info info = cskip_info[i]; - size_t n_true = info.skip_op_true.size(); - size_t n_false = info.skip_op_false.size(); - size_t i_arg = cskip_new[i].i_arg; - rec->ReplaceArg(i_arg++, info.cop ); - rec->ReplaceArg(i_arg++, info.flag ); - rec->ReplaceArg(i_arg++, info.left ); - rec->ReplaceArg(i_arg++, info.right ); - rec->ReplaceArg(i_arg++, n_true ); - rec->ReplaceArg(i_arg++, n_false ); - for(size_t j = 0; j < info.skip_op_true.size(); j++) - { i_op = cskip_info[i].skip_op_true[j]; - // op_info[i_op].usage == yes_usage - CPPAD_ASSERT_UNKNOWN( old2new[i_op].new_op != 0 ); - rec->ReplaceArg(i_arg++, old2new[i_op].new_op ); - } - for(size_t j = 0; j < info.skip_op_false.size(); j++) - { i_op = cskip_info[i].skip_op_false[j]; - // op_info[i_op].usage == yes_usage - CPPAD_ASSERT_UNKNOWN( old2new[i_op].new_op != 0 ); - rec->ReplaceArg(i_arg++, old2new[i_op].new_op ); - } - rec->ReplaceArg(i_arg++, n_true + n_false); -# ifndef NDEBUG - size_t n_arg = 7 + n_true + n_false; - CPPAD_ASSERT_UNKNOWN( cskip_new[i].i_arg + n_arg == i_arg ); -# endif - } - } -} - -} } } // END_CPPAD_LOCAL_OPTIMIZE_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize/record_csum.hpp b/ct_core/include/ct/external/cppad/local/optimize/record_csum.hpp deleted file mode 100644 index 66ba354bd..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize/record_csum.hpp +++ /dev/null @@ -1,256 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_OPTIMIZE_RECORD_CSUM_HPP -# define CPPAD_LOCAL_OPTIMIZE_RECORD_CSUM_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/*! -\file record_csum.hpp -Recording a cummulative cummulative summation. -*/ -# include - -// BEGIN_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -namespace CppAD { namespace local { namespace optimize { -/*! -Recording a cummulative cummulative summation. - -\param var2op -mapping from old variable index to old operator index. - -\param op_info -mapping from old index to operator index to operator information - -\param old2new -mapping from old operator index to information about the new recording. - -\param current -is the index in the old operation sequence for -the variable corresponding to the result for the current operator. -We use the notation i_op = var2op[current]. -It follows that NumRes( op_info[i_op].op ) > 0. -If 0 < j_op < i_op, either op_info[j_op].usage == csum_usage, -op_info[j_op].usage = no_usage, or old2new[j_op].new_var != 0. - -\param npar -is the number of parameters corresponding to the old operation sequence. - -\param par -is a vector of length npar containing the parameters -the old operation sequence; i.e., -given a parameter index i < npar, the corresponding parameter value is par[i]. - -\param rec -is the object that will record the new operations. - -\return -is the operator and variable indices in the new operation sequence. - -\param work -Is temporary work space. On input and output, -work.op_stack, work.add_stack, and work.sub_stack, are all empty. -These stacks are passed in so that they are created once -and then be reused with calls to record_csum. - -\par Assumptions -op_info[i_o].op -must be one of AddpvOp, AddvvOp, SubpvOp, SubvpOp, SubvvOp. -op_info[i_op].usage != no_usage and ! op_info[i_op].usage == csum_usage. -Furthermore op_info[j_op].usage == csum_usage is true from some -j_op that corresponds to a variable that is an argument to -op_info[i_op]. -*/ - -template -struct_size_pair record_csum( - const vector& var2op , - const vector& op_info , - const CppAD::vector& old2new , - size_t current , - size_t npar , - const Base* par , - recorder* rec , - // local information passed so stacks need not be allocated for every call - struct_csum_stacks& work ) -{ - // check assumption about work space - CPPAD_ASSERT_UNKNOWN( work.op_stack.empty() ); - CPPAD_ASSERT_UNKNOWN( work.add_stack.empty() ); - CPPAD_ASSERT_UNKNOWN( work.sub_stack.empty() ); - // - size_t i_op = var2op[current]; - CPPAD_ASSERT_UNKNOWN( ! ( op_info[i_op].usage == csum_usage ) ); - // - size_t i; - OpCode op; - const addr_t* arg; - bool add; - struct struct_csum_variable var; - // - // information corresponding to the root node in the cummulative summation - var.op = op_info[i_op].op; // this operator - var.arg = op_info[i_op].arg; // arguments for this operator - var.add = true; // was parrent operator positive or negative - // - // initialize stack as containing this one operator - work.op_stack.push( var ); - // - // initialize sum of parameter values as zero - Base sum_par(0); - // -# ifndef NDEBUG - bool ok = false; - struct_op_info info = op_info[i_op]; - if( var.op == SubvpOp ) - ok = op_info[ var2op[info.arg[0]] ].usage == csum_usage; - if( var.op == AddpvOp || var.op == SubpvOp ) - ok = op_info[ var2op[info.arg[1]] ].usage == csum_usage; - if( var.op == AddvvOp || var.op == SubvvOp ) - { ok = op_info[ var2op[info.arg[0]] ].usage == csum_usage; - ok |= op_info[ var2op[info.arg[1]] ].usage == csum_usage; - } - CPPAD_ASSERT_UNKNOWN( ok ); -# endif - // - // while there are operators left on the stack - while( ! work.op_stack.empty() ) - { // get this summation operator - var = work.op_stack.top(); - work.op_stack.pop(); - op = var.op; - arg = var.arg; - add = var.add; - // - // process first argument to this operator - switch(op) - { // cases where first argument is a parameter - case AddpvOp: - case SubpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < npar ); - // first argument has same sign as parent node - if( add ) - sum_par += par[arg[0]]; - else sum_par -= par[arg[0]]; - break; - - // cases where first argument is a variable - case AddvvOp: - case SubvpOp: - case SubvvOp: - // - // check if the first argument has csum usage - if( op_info[var2op[arg[0]]].usage == csum_usage ) - { CPPAD_ASSERT_UNKNOWN( - size_t( old2new[ var2op[arg[0]] ].new_var) == 0 - ); - // push the operator corresponding to the first argument - var.op = op_info[ var2op[arg[0]] ].op; - var.arg = op_info[ var2op[arg[0]] ].arg; - // first argument has same sign as parent node - var.add = add; - work.op_stack.push( var ); - } - else - { // there are no nodes below this one - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < current ); - if( add ) - work.add_stack.push(arg[0]); - else work.sub_stack.push(arg[0]); - } - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } - // process second argument to this operator - switch(op) - { // cases where second argument is a parameter - case SubvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < npar ); - // second argument has opposite sign of parent node - if( add ) - sum_par -= par[arg[1]]; - else sum_par += par[arg[1]]; - break; - - // cases where second argument is a variable and has opposite sign - case SubvvOp: - case SubpvOp: - add = ! add; - - // cases where second argument is a variable and has same sign - case AddvvOp: - case AddpvOp: - // check if the second argument has csum usage - if( op_info[var2op[arg[1]]].usage == csum_usage ) - { CPPAD_ASSERT_UNKNOWN( - size_t( old2new[ var2op[arg[1]] ].new_var) == 0 - ); - // push the operator corresoponding to the second arugment - var.op = op_info[ var2op[arg[1]] ].op; - var.arg = op_info[ var2op[arg[1]] ].arg; - var.add = add; - work.op_stack.push( var ); - } - else - { // there are no nodes below this one - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < current ); - if( add ) - work.add_stack.push(arg[1]); - else work.sub_stack.push(arg[1]); - } - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } - } - // number of variables to add in this cummulative sum operator - size_t n_add = work.add_stack.size(); - // number of variables to subtract in this cummulative sum operator - size_t n_sub = work.sub_stack.size(); - // - rec->PutArg(n_add); // arg[0] - rec->PutArg(n_sub); // arg[1] - size_t new_arg = rec->PutPar(sum_par); - rec->PutArg(new_arg); // arg[2] - // addition arguments - for(i = 0; i < n_add; i++) - { CPPAD_ASSERT_UNKNOWN( ! work.add_stack.empty() ); - size_t old_arg = work.add_stack.top(); - new_arg = old2new[ var2op[old_arg] ].new_var; - CPPAD_ASSERT_UNKNOWN( 0 < new_arg && new_arg < current ); - rec->PutArg(new_arg); // arg[3+i] - work.add_stack.pop(); - } - // subtraction arguments - for(i = 0; i < n_sub; i++) - { CPPAD_ASSERT_UNKNOWN( ! work.sub_stack.empty() ); - size_t old_arg = work.sub_stack.top(); - new_arg = old2new[ var2op[old_arg] ].new_var; - CPPAD_ASSERT_UNKNOWN( 0 < new_arg && new_arg < current ); - rec->PutArg(new_arg); // arg[3 + arg[0] + i] - work.sub_stack.pop(); - } - // number of additions plus number of subtractions - rec->PutArg(n_add + n_sub); // arg[3 + arg[0] + arg[1]] - // - // return value - struct_size_pair ret; - ret.i_op = rec->num_op_rec(); - ret.i_var = rec->PutOp(CSumOp); - // - return ret; -} - -} } } // END_CPPAD_LOCAL_OPTIMIZE_NAMESPACE - - -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize/record_pv.hpp b/ct_core/include/ct/external/cppad/local/optimize/record_pv.hpp deleted file mode 100644 index 77aab4874..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize/record_pv.hpp +++ /dev/null @@ -1,105 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_OPTIMIZE_RECORD_PV_HPP -# define CPPAD_LOCAL_OPTIMIZE_RECORD_PV_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/*! -\file record_pv.hpp -Record an operation of the form (parameter op variable). -*/ -// BEGIN_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -namespace CppAD { namespace local { namespace optimize { - -/*! -Record an operation of the form (parameter op variable). - -\param var2op -mapping from old variable index to old operator index. - -\param op_info -mapping from old index to operator index to operator information - -\param old2new -mapping from old operator index to information about the new recording. - -\param current -is the index in the old operation sequence for -the variable corresponding to the result for the current operator. -We use the notation i_op = var2op[current]. -It follows that NumRes( op_info[i_op].op ) > 0. -If 0 < j_op < i_op, either op_info[j_op].csum_connected, -op_info[j_op].usage = 0, or old2new[j_op].new_var != 0. - -\param npar -is the number of parameters corresponding to the old operation sequence. - -\param par -is a vector of length npar containing the parameters -the old operation sequence; i.e., -given a parameter index i < npar, the corresponding parameter value is par[i]. - -\param rec -is the object that will record the new operations. - -\return -is the operator and variable indices in the new operation sequence. - -\param op -is the operator that we are recording which must be one of the following: -AddpvOp, DivpvOp, MulpvOp, PowpvOp, SubpvOp, ZmulpvOp. - -\param arg -is the vector of arguments for this operator. -*/ -template -struct_size_pair record_pv( - const vector& var2op , - const vector& op_info , - const CppAD::vector& old2new , - size_t current , - size_t npar , - const Base* par , - recorder* rec , - OpCode op , - const addr_t* arg ) -{ -# ifndef NDEBUG - switch(op) - { case AddpvOp: - case DivpvOp: - case MulpvOp: - case PowpvOp: - case SubpvOp: - case ZmulpvOp: - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } -# endif - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < npar ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < current ); - addr_t new_arg[2]; - new_arg[0] = rec->PutPar( par[arg[0]] ); - new_arg[1] = old2new[ var2op[arg[1]] ].new_var; - rec->PutArg( new_arg[0], new_arg[1] ); - - struct_size_pair ret; - ret.i_op = rec->num_op_rec(); - ret.i_var = rec->PutOp(op); - CPPAD_ASSERT_UNKNOWN( 0 < new_arg[1] && size_t(new_arg[1]) < ret.i_var ); - return ret; -} - -} } } // END_CPPAD_LOCAL_OPTIMIZE_NAMESPACE - - -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize/record_vp.hpp b/ct_core/include/ct/external/cppad/local/optimize/record_vp.hpp deleted file mode 100644 index 42e6ffd6b..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize/record_vp.hpp +++ /dev/null @@ -1,104 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_OPTIMIZE_RECORD_VP_HPP -# define CPPAD_LOCAL_OPTIMIZE_RECORD_VP_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/*! -\file record_vp.hpp -Record an operation of the form (variable op parameter). -*/ -// BEGIN_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -namespace CppAD { namespace local { namespace optimize { - - -/*! -Record an operation of the form (variable op parameter). - -\param var2op -mapping from old variable index to old operator index. - -\param op_info -mapping from old index to operator index to operator information - -\param old2new -mapping from old operator index to information about the new recording. - -\param current -is the index in the old operation sequence for -the variable corresponding to the result for the current operator. -We use the notation i_op = var2op[current]. -It follows that NumRes( op_info[i_op].op ) > 0. -If 0 < j_op < i_op, either op_info[j_op].csum_connected, -op_info[j_op].usage = 0, or old2new[j_op].new_var != 0. - -\param npar -is the number of parameters corresponding to the old operation sequence. - -\param par -is a vector of length npar containing the parameters -the old operation sequence; i.e., -given a parameter index i < npar, the corresponding parameter value is par[i]. - -\param rec -is the object that will record the new operations. - -\return -is the operator and variable indices in the new operation sequence. - -\param op -is the operator that we are recording which must be one of the following: -DivvpOp, PowvpOp, SubvpOp, ZmulvpOp. - -\param arg -is the vector of arguments for this operator. -*/ -template -struct_size_pair record_vp( - const vector& var2op , - const vector& op_info , - const CppAD::vector& old2new , - size_t current , - size_t npar , - const Base* par , - recorder* rec , - OpCode op , - const addr_t* arg ) -{ -# ifndef NDEBUG - switch(op) - { case DivvpOp: - case PowvpOp: - case SubvpOp: - case ZmulvpOp: - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } -# endif - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < current ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < npar ); - addr_t new_arg[2]; - new_arg[0] = old2new[ var2op[arg[0]] ].new_var; - new_arg[1] = rec->PutPar( par[arg[1]] ); - rec->PutArg( new_arg[0], new_arg[1] ); - - struct_size_pair ret; - ret.i_op = rec->num_op_rec(); - ret.i_var = rec->PutOp(op); - CPPAD_ASSERT_UNKNOWN( 0 < new_arg[0] && size_t(new_arg[0]) < ret.i_var ); - return ret; -} - -} } } // END_CPPAD_LOCAL_OPTIMIZE_NAMESPACE - - -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize/record_vv.hpp b/ct_core/include/ct/external/cppad/local/optimize/record_vv.hpp deleted file mode 100644 index 521cb9bd3..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize/record_vv.hpp +++ /dev/null @@ -1,105 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_OPTIMIZE_RECORD_VV_HPP -# define CPPAD_LOCAL_OPTIMIZE_RECORD_VV_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/*! -\file record_vv.hpp -Record an operation of the form (variable op variable). -*/ -// BEGIN_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -namespace CppAD { namespace local { namespace optimize { -/*! -Record an operation of the form (variable op variable). - -\param var2op -mapping from old variable index to old operator index. - -\param op_info -mapping from old index to operator index to operator information - -\param old2new -mapping from old operator index to information about the new recording. - -\param current -is the index in the old operation sequence for -the variable corresponding to the result for the current operator. -We use the notation i_op = var2op[current]. -It follows that NumRes( op_info[i_op].op ) > 0. -If 0 < j_op < i_op, either op_info[j_op].csum_connected, -op_info[j_op].usage = 0, or old2new[j_op].new_var != 0. - -\param npar -is the number of parameters corresponding to the old operation sequence. - -\param par -is a vector of length npar containing the parameters -the old operation sequence; i.e., -given a parameter index i < npar, the corresponding parameter value is par[i]. - -\param rec -is the object that will record the new operations. - -\return -is the operator and variable indices in the new operation sequence. - -\param op -is the operator that we are recording which must be one of the following: -AddvvOp, DivvvOp, MulvvOp, PowvvOp, SubvvOp, ZmulvvOp. - -\param arg -is the vector of arguments for this operator. -*/ -template -struct_size_pair record_vv( - const vector& var2op , - const vector& op_info , - const CppAD::vector& old2new , - size_t current , - size_t npar , - const Base* par , - recorder* rec , - OpCode op , - const addr_t* arg ) -{ -# ifndef NDEBUG - switch(op) - { case AddvvOp: - case DivvvOp: - case MulvvOp: - case PowvvOp: - case SubvvOp: - case ZmulvvOp: - break; - - default: - CPPAD_ASSERT_UNKNOWN(false); - } -# endif - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < current ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < current ); - addr_t new_arg[2]; - new_arg[0] = old2new[ var2op[arg[0]] ].new_var; - new_arg[1] = old2new[ var2op[arg[1]] ].new_var; - rec->PutArg( new_arg[0], new_arg[1] ); - - struct_size_pair ret; - ret.i_op = rec->num_op_rec(); - ret.i_var = rec->PutOp(op); - CPPAD_ASSERT_UNKNOWN( 0 < new_arg[0] && size_t(new_arg[0]) < ret.i_var ); - CPPAD_ASSERT_UNKNOWN( 0 < new_arg[1] && size_t(new_arg[1]) < ret.i_var ); - return ret; -} - -} } } // END_CPPAD_LOCAL_OPTIMIZE_NAMESPACE - - -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize/size_pair.hpp b/ct_core/include/ct/external/cppad/local/optimize/size_pair.hpp deleted file mode 100644 index b97964ab2..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize/size_pair.hpp +++ /dev/null @@ -1,32 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_OPTIMIZE_SIZE_PAIR_HPP -# define CPPAD_LOCAL_OPTIMIZE_SIZE_PAIR_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/*! -\file size_pair.hpp -Information for one variable and one operation sequence. -*/ -// BEGIN_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -namespace CppAD { namespace local { namespace optimize { - -/*! -\file size_pair.hpp -Information for one variable in one operation sequence. -*/ -struct struct_size_pair { - size_t i_op; /// operator index for this variable - size_t i_var; /// variable index for this variable -}; - -} } } // END_CPPAD_LOCAL_OPTIMIZE_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/optimize/usage.hpp b/ct_core/include/ct/external/cppad/local/optimize/usage.hpp deleted file mode 100644 index 6fc569718..000000000 --- a/ct_core/include/ct/external/cppad/local/optimize/usage.hpp +++ /dev/null @@ -1,35 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_OPTIMIZE_USAGE_HPP -# define CPPAD_LOCAL_OPTIMIZE_USAGE_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -namespace CppAD { namespace local { namespace optimize { - -enum enum_usage { - /// This operator is not used. - no_usage, - - /// This operator is used one or more times. - yes_usage, - - /*! - This operator is only used once, it is a summation operator, - and its parrent is a summation operator. Furthermore, its result is not - a dependent variable. Hence case it can be removed as part of a - cumulative summation starting at its parent or above. - */ - csum_usage -}; - -} } } // END_CPPAD_LOCAL_OPTIMIZE_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/ordered.hpp b/ct_core/include/ct/external/cppad/local/ordered.hpp deleted file mode 100644 index 4ee1a5209..000000000 --- a/ct_core/include/ct/external/cppad/local/ordered.hpp +++ /dev/null @@ -1,102 +0,0 @@ -// $Id: ordered.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_ORDERED_HPP -# define CPPAD_ORDERED_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -/*! -\file ordered.hpp -Check and AD values ordering properties relative to zero. -*/ - -// GreaterThanZero ============================================================ -/*! -Check if an AD is greater than zero. - -\param x -value we are checking. - -\return -returns true iff the \c x is greater than zero. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool GreaterThanZero(const AD &x) -{ return GreaterThanZero(x.value_); } -// GreaterThanOrZero ========================================================= -/*! -Check if an AD is greater than or equal zero. - -\param x -value we are checking. - -\return -returns true iff the \c x is greater than or equal zero. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool GreaterThanOrZero(const AD &x) -{ return GreaterThanOrZero(x.value_); } -// LessThanZero ============================================================ -/*! -Check if an AD is less than zero. - -\param x -value we are checking. - -\return -returns true iff the \c x is less than zero. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool LessThanZero(const AD &x) -{ return LessThanZero(x.value_); } -// LessThanOrZero ========================================================= -/*! -Check if an AD is less than or equal zero. - -\param x -value we are checking. - -\return -returns true iff the \c x is less than or equal zero. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool LessThanOrZero(const AD &x) -{ return LessThanOrZero(x.value_); } -// abs_geq ========================================================= -/*! -Check if absolute value of one AD is greater or equal another. - -\param x -value we are checking if it is greater than or equal other. - -\param y -value we are checking if it is less than other. - -\return -returns true iff the absolute value of \c x is greater than or equal -absolute value of \c y. -*/ -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -bool abs_geq(const AD& x, const AD& y) -{ return abs_geq(x.value_, y.value_); } -// ============================================================================ -} // END_CPPAD_NAMESPACE -# endif - diff --git a/ct_core/include/ct/external/cppad/local/par_var.hpp b/ct_core/include/ct/external/cppad/local/par_var.hpp deleted file mode 100644 index 76f8fda32..000000000 --- a/ct_core/include/ct/external/cppad/local/par_var.hpp +++ /dev/null @@ -1,119 +0,0 @@ -// $Id: par_var.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_PAR_VAR_HPP -# define CPPAD_PAR_VAR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* ---------------------------------------------------------------------------- - -$begin ParVar$$ -$spell - VecAD - const - bool -$$ - -$section Is an AD Object a Parameter or Variable$$ - -$head Syntax$$ -$icode%b% = Parameter(%x%)%$$ -$pre -$$ -$icode%b% = Variable(%x%)%$$ - - -$head Purpose$$ -Determine if $icode x$$ is a -$cref/parameter/glossary/Parameter/$$ or -$cref/variable/glossary/Variable/$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const AD<%Base%> &%x% - const VecAD<%Base%> &%x% -%$$ - -$head b$$ -The return value $icode b$$ has prototype -$codei% - bool %b% -%$$ -The return value for $code Parameter$$ ($code Variable$$) -is true if and only if $icode x$$ is a parameter (variable). -Note that a $cref/VecAD/VecAD/$$ object -is a variable if any element of the vector depends on the independent -variables. - -$head Operation Sequence$$ -The result of this operation is not an -$cref/AD of Base/glossary/AD of Base/$$ object. -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Example$$ -$children% - example/par_var.cpp -%$$ -The file -$cref par_var.cpp$$ -contains an example and test of these functions. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -namespace CppAD { - // Parameter - template - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION - bool Parameter(const AD &x) - { if( x.tape_id_ == 0 ) - return true; - size_t thread = size_t(x.tape_id_ % CPPAD_MAX_NUM_THREADS); - return x.tape_id_ != *AD::tape_id_ptr(thread); - } - - template - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION - bool Parameter(const VecAD &x) - { if( x.tape_id_ == 0 ) - return true; - size_t thread = size_t(x.tape_id_ % CPPAD_MAX_NUM_THREADS); - return x.tape_id_ != *AD::tape_id_ptr(thread); - } - - // Variable - template - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION - bool Variable(const AD &x) - { if( x.tape_id_ == 0 ) - return false; - size_t thread = size_t(x.tape_id_ % CPPAD_MAX_NUM_THREADS); - return x.tape_id_ == *AD::tape_id_ptr(thread); - } - - template - CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION - bool Variable(const VecAD &x) - { if( x.tape_id_ == 0 ) - return false; - size_t thread = size_t(x.tape_id_ % CPPAD_MAX_NUM_THREADS); - return x.tape_id_ == *AD::tape_id_ptr(thread); - } -} -// END CppAD namespace - - -# endif diff --git a/ct_core/include/ct/external/cppad/local/parallel_ad.hpp b/ct_core/include/ct/external/cppad/local/parallel_ad.hpp deleted file mode 100644 index 1df93db9c..000000000 --- a/ct_core/include/ct/external/cppad/local/parallel_ad.hpp +++ /dev/null @@ -1,118 +0,0 @@ -// $Id: parallel_ad.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_PARALLEL_AD_HPP -# define CPPAD_PARALLEL_AD_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin parallel_ad$$ -$spell - CppAD - num - std -$$ - -$section Enable AD Calculations During Parallel Mode$$ - -$head Syntax$$ -$codei%parallel_ad<%Base%>()%$$ - -$head Purpose$$ -The function -$codei%parallel_ad<%Base%>()%$$ -must be called before any $codei%AD<%Base>%$$ objects are used -in $cref/parallel/ta_in_parallel/$$ mode. -In addition, if this routine is called after one is done using -parallel mode, it will free extra memory used to keep track of -the multiple $codei%AD<%Base%>%$$ tapes required for parallel execution. - -$head Discussion$$ -By default, for each $codei%AD<%Base%>%$$ class there is only one -tape that records $cref/AD of Base/glossary/AD of Base/$$ operations. -This tape is a global variable and hence it cannot be used -by multiple threads at the same time. -The $cref/parallel_setup/ta_parallel_setup/$$ function informs CppAD of the -maximum number of threads that can be active in parallel mode. -This routine does extra setup -(and teardown) for the particular $icode Base$$ type. - -$head CheckSimpleVector$$ -This routine has the side effect of calling the routines -$codei% - CheckSimpleVector< %Type%, CppAD::vector<%Type%> >() -%$$ -where $icode Type$$ is $icode Base$$ and $codei%AD<%Base%>%$$. - -$head Example$$ -The files -$cref team_openmp.cpp$$, -$cref team_bthread.cpp$$, and -$cref team_pthread.cpp$$, -contain examples and tests that implement this function. - -$head Restriction$$ -This routine cannot be called in parallel mode or while -there is a tape recording $codei%AD<%Base%>%$$ operations. - -$end ------------------------------------------------------------------------------ -*/ - -# include - -// BEGIN CppAD namespace -namespace CppAD { - -/*! -Enable parallel execution mode with AD by initializing -static variables that my be used. -*/ - -template -void parallel_ad(void) -{ CPPAD_ASSERT_KNOWN( - ! thread_alloc::in_parallel() , - "parallel_ad must be called before entering parallel execution mode." - ); - CPPAD_ASSERT_KNOWN( - AD::tape_ptr() == CPPAD_NULL , - "parallel_ad cannot be called while a tape recording is in progress" - ); - - // ensure statics in following functions are initialized - elapsed_seconds(); - ErrorHandler::Current(); - NumArg(BeginOp); - NumRes(BeginOp); - one_element_std_set(); - two_element_std_set(); - - // the sparse_pack class has member functions with static data - sparse_pack sp; - sp.resize(1, 1); // so can call add_element - sp.add_element(0, 0); // has static data - sp.begin(0); // so can call next_element - sp.next_element(); // has static data - sp.clear(0); // has static data - sp.is_element(0, 0); // has static data - - // statics that depend on the value of Base - AD::tape_id_handle(0); - AD::tape_handle(0); - AD::tape_manage(tape_manage_clear); - discrete::List(); - CheckSimpleVector< Base, CppAD::vector >(); - CheckSimpleVector< AD, CppAD::vector< AD > >(); - -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/parameter_op.hpp b/ct_core/include/ct/external/cppad/local/parameter_op.hpp deleted file mode 100644 index 628bebf85..000000000 --- a/ct_core/include/ct/external/cppad/local/parameter_op.hpp +++ /dev/null @@ -1,90 +0,0 @@ -// $Id: parameter_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_PARAMETER_OP_HPP -# define CPPAD_PARAMETER_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file parameter_op.hpp -Zero order forward mode for ParOp -*/ - - -/*! -Compute zero order forward mode Taylor coefficient for result of op = ParOp. - -The C++ source code corresponding to this operation is one of the following -\verbatim - ADFun f(x, y) - f.Dependent(x, y) -\endverbatim -where some of the components of the vector y are parameters. - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base . - -\param i_z -variable index corresponding to the result for this operation; -i.e. the row index in \a taylor corresponding to the component of y -that is a parameter. - -\param arg -\a arg[0] -\n -index corresponding to the parameter value for this operator. - -\param num_par -is the number of parameters in \a parameter. - -\param parameter -\b Input: \a parameter[ \a arg[0] ] is the value of a component -of y that is a parameter. - -\param cap_order -number of colums in the matrix containing all the Taylor coefficients. - -\param taylor -\b Output: \a taylor [ \a i_z * \a cap_order + 0 ] -is the zero order Taylor coefficient corresponding to z. - -\par Checked Assertions where op is the unary operator with one result: -\li NumArg(op) == 1 -\li NumRes(op) == 1 -\li \a size_t(arg[0]) < num_par -\li \a 0 < \a cap_order -*/ -template -inline void forward_par_op_0( - size_t i_z , - const addr_t* arg , - size_t num_par , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ParOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ParOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - Base* z = taylor + i_z * cap_order; - - z[0] = parameter[ arg[0] ]; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/player.hpp b/ct_core/include/ct/external/cppad/local/player.hpp deleted file mode 100644 index 40882b6df..000000000 --- a/ct_core/include/ct/external/cppad/local/player.hpp +++ /dev/null @@ -1,690 +0,0 @@ -// $Id: player.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_PLAYER_HPP -# define CPPAD_PLAYER_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file player.hpp -File used to define the player class. -*/ - - -/*! -Class used to store and play back an operation sequence recording. - -\tparam Base -These were AD< \a Base > operations when recorded. Operations during playback -are done using the type \a Base . -*/ -template -class player { - -// -------------- Variables that define the recording ----------------------- -private: - /// Number of variables in the recording. - size_t num_var_rec_; - - /// number of vecad load opeations in the reconding - size_t num_load_op_rec_; - - /// Number of VecAD vectors in the recording - size_t num_vecad_vec_rec_; - - /// The operators in the recording. - pod_vector op_rec_; - - /// The VecAD indices in the recording. - pod_vector vecad_ind_rec_; - - /// The operation argument indices in the recording - pod_vector op_arg_rec_; - - /// The parameters in the recording. - /// Note that Base may not be plain old data, so use false in consructor. - pod_vector par_rec_; - - /// Character strings ('\\0' terminated) in the recording. - pod_vector text_rec_; - - -// --------------- Functions used to create and maniplate a recording ------- -public: - /// Default constructor - player(void) : - num_var_rec_(0) , - num_load_op_rec_(0) , - op_rec_( std::numeric_limits::max() ) , - vecad_ind_rec_( std::numeric_limits::max() ) , - op_arg_rec_( std::numeric_limits::max() ) , - par_rec_( std::numeric_limits::max() ) , - text_rec_( std::numeric_limits::max() ) - { } - - /// Destructor - ~player(void) - { } - - // =============================================================== - /*! - Moving an operation sequence from a recorder to a player - - \param rec - the object that was used to record the operation sequence. After this - operation, the state of the recording is no longer defined. For example, - the \c pod_vector member variables in \c this have been swapped with - \c rec . - */ - void get(recorder& rec) - { size_t i; - - // just set size_t values - num_var_rec_ = rec.num_var_rec_; - num_load_op_rec_ = rec.num_load_op_rec_; - - // op_rec_ - op_rec_.swap(rec.op_rec_); - - // vec_ind_rec_ - vecad_ind_rec_.swap(rec.vecad_ind_rec_); - - // op_arg_rec_ - op_arg_rec_.swap(rec.op_arg_rec_); - - // par_rec_ - par_rec_.swap(rec.par_rec_); - - // text_rec_ - text_rec_.swap(rec.text_rec_); - - // set the number of VecAD vectors - num_vecad_vec_rec_ = 0; - for(i = 0; i < vecad_ind_rec_.size(); i += vecad_ind_rec_[i] + 1) - num_vecad_vec_rec_++; - - // vecad_ind_rec_ contains size of each VecAD followed by - // the parameter indices used to iniialize it. - CPPAD_ASSERT_UNKNOWN( i == vecad_ind_rec_.size() ); - } - // =============================================================== - /*! - Copying an operation sequence from one player to another - - \param play - the object that contains the operatoion sequence to copy. - */ - void operator=(const player& play) - { - num_var_rec_ = play.num_var_rec_; - num_load_op_rec_ = play.num_load_op_rec_; - op_rec_ = play.op_rec_; - num_vecad_vec_rec_ = play.num_vecad_vec_rec_; - vecad_ind_rec_ = play.vecad_ind_rec_; - op_arg_rec_ = play.op_arg_rec_; - par_rec_ = play.par_rec_; - text_rec_ = play.text_rec_; - } - // =============================================================== - - /// Erase all information in an operation sequence player. - void Erase(void) - { - num_var_rec_ = 0; - num_load_op_rec_ = 0; - num_vecad_vec_rec_ = 0; - - op_rec_.erase(); - vecad_ind_rec_.erase(); - op_arg_rec_.erase(); - par_rec_.erase(); - text_rec_.erase(); - } - -public: - /*! - \brief - Old method of fetching an operator from the recording. - - \return - the i-th operator in the recording. - - \param i - the index of the operator in recording - */ - OpCode GetOp (size_t i) const - { return OpCode(op_rec_[i]); } - - /*! - \brief - Fetch a VecAD index from the recording. - - \return - the i-th VecAD index in the recording. - - \param i - the index of the VecAD index in recording - */ - size_t GetVecInd (size_t i) const - { return vecad_ind_rec_[i]; } - - /*! - \brief - Fetch a parameter from the recording. - - \return - the i-th parameter in the recording. - - \param i - the index of the parameter in recording - */ - Base GetPar(size_t i) const - { return par_rec_[i]; } - - /*! - \brief - Fetch entire parameter vector from the recording. - - \return - the entire parameter vector. - - */ - const Base* GetPar(void) const - { return par_rec_.data(); } - - /*! - \brief - Fetch a '\\0' terminated string from the recording. - - \return - the beginning of the string. - - \param i - the index where the string begins. - */ - const char *GetTxt(size_t i) const - { CPPAD_ASSERT_UNKNOWN(i < text_rec_.size() ); - return text_rec_.data() + i; - } - - /// Fetch number of variables in the recording. - size_t num_var_rec(void) const - { return num_var_rec_; } - - /// Fetch number of vecad load operations - size_t num_load_op_rec(void) const - { return num_load_op_rec_; } - - /// Fetch number of operators in the recording. - size_t num_op_rec(void) const - { return op_rec_.size(); } - - /// Fetch number of VecAD indices in the recording. - size_t num_vec_ind_rec(void) const - { return vecad_ind_rec_.size(); } - - /// Fetch number of VecAD vectors in the recording - size_t num_vecad_vec_rec(void) const - { return num_vecad_vec_rec_; } - - /// Fetch number of argument indices in the recording. - size_t num_op_arg_rec(void) const - { return op_arg_rec_.size(); } - - /// Fetch number of parameters in the recording. - size_t num_par_rec(void) const - { return par_rec_.size(); } - - /// Fetch number of characters (representing strings) in the recording. - size_t num_text_rec(void) const - { return text_rec_.size(); } - - /// Fetch a rough measure of amount of memory used to store recording - /// (just lengths, not capacities). - size_t Memory(void) const - { return op_rec_.size() * sizeof(OpCode) - + op_arg_rec_.size() * sizeof(addr_t) - + par_rec_.size() * sizeof(Base) - + text_rec_.size() * sizeof(char) - + vecad_ind_rec_.size() * sizeof(addr_t) - ; - } - -// ------------- Variables used for new methog of playing back a recording --- -private: - /// Current operator - OpCode op_; - - /// Index in recording corresponding to current operator - size_t op_index_; - - /// Current offset of the argument indices in op_arg_rec_ - const addr_t* op_arg_; - - /// Index for primary (last) variable corresponding to current operator - size_t var_index_; - -// ----------- Functions used in new method for palying back a recording --- -public: - /*! - Start a play back of the recording during a forward sweep. - - Use repeated calls to forward_next to play back one operator at a time. - - \param op [out] - The input value of \c op does not matter. Its output value is the - first operator in the recording; i.e., BeginOp. - - \param op_arg [out] - The input value of \c op_arg does not matter. Its output value is the - beginning of the vector of argument indices for the first operation; - i.e., 0 - - \param op_index [out] - The input value of \c op_index does not matter. Its output value - is the index of the next first operator in the recording; i.e., 0. - - \param var_index [out] - The input value of \c var_index does not matter. Its output value is the - index of the primary (last) result corresponding to the the first - operator (which must be a BeginOp); i.e., 0. - */ - void forward_start( - OpCode& op, const addr_t*& op_arg, size_t& op_index, size_t& var_index) - { - op = op_ = OpCode( op_rec_[0] ); - op_arg = op_arg_ = op_arg_rec_.data(); - op_index = op_index_ = 0; - var_index = var_index_ = 0; - - CPPAD_ASSERT_UNKNOWN( op_ == BeginOp ); - CPPAD_ASSERT_NARG_NRES(op_, 1, 1); - - return; - } - - /*! - Fetch the next operator during a forward sweep. - - Use forward_start to initialize to the first operator; i.e., - the BeginOp at the beginning of the recording. - We use the notation forward_routine to denote the set - forward_start, forward_next, forward_csum, forward_cskip. - - \param op [in,out] - The input value of \c op must be its output value from the - previous call to a forward_routine. - Its output value is the next operator in the recording. - For speed, \c forward_next does not check for the special cases - where op == CSumOp or op == CSkipOp. In these cases, - the other return values from \c forward_next must be corrected by a call - to \c forward_csum or \c forward_cskip respectively. - - \param op_arg [in,out] - The input value of \c op_arg must be its output value form the - previous call to a forward routine. - Its output value is the - beginning of the vector of argument indices for this operation. - - \param op_index [in,out] - The input value of \c op_index must be its output value form the - previous call to a forward routine. - Its output value is the index of the next operator in the recording. - Thus the ouput value following the previous call to forward_start is one. - In addition, - the output value increases by one with each call to forward_next. - - \param var_index [in,out] - The input value of \c var_index must be its output value form the - previous call to a forward routine. - Its output value is the - index of the primary (last) result corresponding to the operator op. - */ - void forward_next( - OpCode& op, const addr_t*& op_arg, size_t& op_index, size_t& var_index) - { using CppAD::NumRes; - using CppAD::NumArg; - CPPAD_ASSERT_UNKNOWN( op_ == op ); - CPPAD_ASSERT_UNKNOWN( op_arg == op_arg_ ); - CPPAD_ASSERT_UNKNOWN( op_index == op_index_ ); - CPPAD_ASSERT_UNKNOWN( var_index == var_index_ ); - - // index for the next operator - op_index = ++op_index_; - - // first argument for next operator - op_arg = op_arg_ += NumArg(op_); - - // next operator - op = op_ = OpCode( op_rec_[ op_index_ ] ); - - // index for last result for next operator - var_index = var_index_ += NumRes(op); - - - CPPAD_ASSERT_UNKNOWN( op_arg_rec_.data() <= op_arg_ ); - CPPAD_ASSERT_UNKNOWN( - op_arg_ + NumArg(op) <= op_arg_rec_.data() + op_arg_rec_.size() - ); - CPPAD_ASSERT_UNKNOWN( var_index_ < num_var_rec_ ); - } - /*! - Correct \c forward_next return values when op == CSumOp. - - \param op [in] - The input value of op must be the return value from the previous - call to \c forward_next and must be \c CSumOp. It is not modified. - - \param op_arg [in,out] - The input value of \c op_arg must be the return value from the - previous call to \c forward_next. Its output value is the - beginning of the vector of argument indices for the next operation. - - \param op_index [in] - The input value of \c op_index does must be the return value from the - previous call to \c forward_next. Its is not modified. - - \param var_index [in,out] - The input value of \c var_index must be the return value from the - previous call to \c forward_next. It is not modified. - */ - void forward_csum( - OpCode& op, const addr_t*& op_arg, size_t& op_index, size_t& var_index) - { using CppAD::NumRes; - using CppAD::NumArg; - CPPAD_ASSERT_UNKNOWN( op_ == op ); - CPPAD_ASSERT_UNKNOWN( op_arg == op_arg_ ); - CPPAD_ASSERT_UNKNOWN( op_index == op_index_ ); - CPPAD_ASSERT_UNKNOWN( var_index == var_index_ ); - - CPPAD_ASSERT_UNKNOWN( op == CSumOp ); - CPPAD_ASSERT_UNKNOWN( NumArg(CSumOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( - op_arg[0] + op_arg[1] == op_arg[ 3 + op_arg[0] + op_arg[1] ] - ); - /* - The only thing that really needs fixing is op_arg_. - Actual number of arugments for this operator is - op_arg[0] + op_arg[1] + 4. - We must change op_arg_ so that when you add NumArg(CSumOp) - you get first argument for next operator in sequence. - */ - op_arg = op_arg_ += op_arg[0] + op_arg[1] + 4; - - CPPAD_ASSERT_UNKNOWN( op_arg_rec_.data() <= op_arg_ ); - CPPAD_ASSERT_UNKNOWN( - op_arg_ + NumArg(op) <= op_arg_rec_.data() + op_arg_rec_.size() - ); - CPPAD_ASSERT_UNKNOWN( var_index_ < num_var_rec_ ); - } - /*! - Correct \c forward_next return values when op == CSkipOp. - - \param op [in] - The input value of op must be the return value from the previous - call to \c forward_next and must be \c CSkipOp. It is not modified. - - \param op_arg [in,out] - The input value of \c op_arg must be the return value from the - previous call to \c forward_next. Its output value is the - beginning of the vector of argument indices for the next operation. - - \param op_index [in] - The input value of \c op_index does must be the return value from the - previous call to \c forward_next. Its is not modified. - - \param var_index [in,out] - The input value of \c var_index must be the return value from the - previous call to \c forward_next. It is not modified. - */ - void forward_cskip( - OpCode& op, const addr_t*& op_arg, size_t& op_index, size_t& var_index) - { using CppAD::NumRes; - using CppAD::NumArg; - CPPAD_ASSERT_UNKNOWN( op_ == op ); - CPPAD_ASSERT_UNKNOWN( op_arg == op_arg_ ); - CPPAD_ASSERT_UNKNOWN( op_index == op_index_ ); - CPPAD_ASSERT_UNKNOWN( var_index == var_index_ ); - - CPPAD_ASSERT_UNKNOWN( op == CSkipOp ); - CPPAD_ASSERT_UNKNOWN( NumArg(CSkipOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( - op_arg[4] + op_arg[5] == op_arg[ 6 + op_arg[4] + op_arg[5] ] - ); - /* - The only thing that really needs fixing is op_arg_. - Actual number of arugments for this operator is - 7 + op_arg[4] + op_arg[5] - We must change op_arg_ so that when you add NumArg(CSkipOp) - you get first argument for next operator in sequence. - */ - op_arg = op_arg_ += 7 + op_arg[4] + op_arg[5]; - - CPPAD_ASSERT_UNKNOWN( op_arg_rec_.data() <= op_arg_ ); - CPPAD_ASSERT_UNKNOWN( - op_arg_ + NumArg(op) <= op_arg_rec_.data() + op_arg_rec_.size() - ); - CPPAD_ASSERT_UNKNOWN( var_index_ < num_var_rec_ ); - } - /*! - Start a play back of the recording during a reverse sweep. - - Use repeated calls to reverse_next to play back one operator at a time. - - \param op [out] - The input value of \c op does not matter. Its output value is the - last operator in the recording; i.e., EndOp. - - \param op_arg [out] - The input value of \c op_arg does not matter. Its output value is the - beginning of the vector of argument indices for the last operation; - (there are no arguments for the last operation so \a op_arg is invalid). - - \param op_index [out[ - The input value of \c op_index does not matter. Its output value - is the index of the last operator in the recording. - - \param var_index [out] - The input value of \c var_index does not matter. Its output value is the - index of the primary (last) result corresponding to the the last - operator (which must be a EndOp). - (there are no results for the last operation so \a var_index is invalid). - */ - - void reverse_start( - OpCode& op, const addr_t*& op_arg, size_t& op_index, size_t& var_index) - { - op_arg = op_arg_ = op_arg_rec_.data() + op_arg_rec_.size(); - op_index = op_index_ = op_rec_.size() - 1; - var_index = var_index_ = num_var_rec_ - 1; - op = op_ = OpCode( op_rec_[ op_index_ ] ); - CPPAD_ASSERT_UNKNOWN( op_ == EndOp ); - CPPAD_ASSERT_NARG_NRES(op, 0, 0); - return; - } - - /*! - Fetch the next operator during a reverse sweep. - - Use reverse_start to initialize to reverse play back. - The first call to reverse_next (after reverse_start) will give the - last operator in the recording. - We use the notation reverse_routine to denote the set - reverse_start, reverse_next, reverse_csum, reverse_cskip. - - \param op [in,out] - The input value of \c op must be its output value from the - previous call to a reverse_routine. - Its output value is the next operator in the recording (in reverse order). - The last operator sets op equal to EndOp. - - \param op_arg [in,out] - The input value of \c op_arg must be its output value from the - previous call to a reverse_routine. - Its output value is the - beginning of the vector of argument indices for this operation. - The last operator sets op_arg equal to the beginning of the - argument indices for the entire recording. - For speed, \c reverse_next does not check for the special cases - op == CSumOp or op == CSkipOp. In these cases, the other - return values from \c reverse_next must be corrected by a call to - \c reverse_csum or \c reverse_cskip respectively. - - - \param op_index [in,out] - The input value of \c op_index must be its output value from the - previous call to a reverse_routine. - Its output value - is the index of this operator in the recording. Thus the output - value following the previous call to reverse_start is equal to - the number of variables in the recording minus one. - In addition, the output value decreases by one with each call to - reverse_next. - The last operator sets op_index equal to 0. - - \param var_index [in,out] - The input value of \c var_index must be its output value from the - previous call to a reverse_routine. - Its output value is the - index of the primary (last) result corresponding to the operator op. - The last operator sets var_index equal to 0 (corresponding to BeginOp - at beginning of operation sequence). - */ - void reverse_next( - OpCode& op, const addr_t*& op_arg, size_t& op_index, size_t& var_index) - { using CppAD::NumRes; - using CppAD::NumArg; - CPPAD_ASSERT_UNKNOWN( op_ == op ); - CPPAD_ASSERT_UNKNOWN( op_arg == op_arg_ ); - CPPAD_ASSERT_UNKNOWN( op_index == op_index_ ); - CPPAD_ASSERT_UNKNOWN( var_index == var_index_ ); - - // index of the last result for the next operator - CPPAD_ASSERT_UNKNOWN( var_index_ >= NumRes(op_) ); - var_index = var_index_ -= NumRes(op_); - - // next operator - CPPAD_ASSERT_UNKNOWN( op_index_ > 0 ); - op_index = --op_index_; // index - op = op_ = OpCode( op_rec_[ op_index_ ] ); // value - - // first argument for next operator - op_arg = op_arg_ -= NumArg(op); - CPPAD_ASSERT_UNKNOWN( op_arg_rec_.data() <= op_arg_ ); - CPPAD_ASSERT_UNKNOWN( - op_arg_ + NumArg(op) <= op_arg_rec_.data() + op_arg_rec_.size() - ); - } - /*! - Correct \c reverse_next return values when op == CSumOp. - - \param op [in] - The input value of \c op must be the return value from the previous - call to \c reverse_next and must be \c CSumOp. It is not modified. - - \param op_arg [in,out] - The input value of \c op_arg must be the return value from the - previous call to \c reverse_next. Its output value is the - beginning of the vector of argument indices for this operation. - - \param op_index [in] - The input value of \c op_index must be the return value from the - previous call to \c reverse_next. It is not modified. - - \param var_index [in] - The input value of \c var_index must be the return value from the - previous call to \c reverse_next. It is not modified. - */ - - void reverse_csum( - OpCode& op, const addr_t*& op_arg, size_t& op_index, size_t& var_index) - { using CppAD::NumRes; - using CppAD::NumArg; - CPPAD_ASSERT_UNKNOWN( op_ == op ); - CPPAD_ASSERT_UNKNOWN( op_arg == op_arg_ ); - CPPAD_ASSERT_UNKNOWN( op_index == op_index_ ); - CPPAD_ASSERT_UNKNOWN( var_index == var_index_ ); - - CPPAD_ASSERT_UNKNOWN( op == CSumOp ); - CPPAD_ASSERT_UNKNOWN( NumArg(CSumOp) == 0 ); - /* - The variables that need fixing are op_arg_ and op_arg. Currently, - op_arg points to the last argument for the previous operator. - */ - // last argument for this csum operation - --op_arg; - // first argument for this csum operation - op_arg = op_arg_ -= (op_arg[0] + 4); - // now op_arg points to the first argument for this csum operator - - CPPAD_ASSERT_UNKNOWN( - op_arg[0] + op_arg[1] == op_arg[ 3 + op_arg[0] + op_arg[1] ] - ); - - CPPAD_ASSERT_UNKNOWN( op_index_ < op_rec_.size() ); - CPPAD_ASSERT_UNKNOWN( op_arg_rec_.data() <= op_arg_ ); - CPPAD_ASSERT_UNKNOWN( var_index_ < num_var_rec_ ); - } - /*! - Correct \c reverse_next return values when op == CSkipOp. - - - \param op [int] - The input value of \c op must be the return value from the previous - call to \c reverse_next and must be \c CSkipOp. It is not modified. - - \param op_arg [in,out] - The input value of \c op_arg must be the return value from the - previous call to \c reverse_next. Its output value is the - beginning of the vector of argument indices for this operation. - - \param op_index [in] - The input value of \c op_index must be the return value from the - previous call to \c reverse_next. It is not modified. - - \param var_index [in] - The input value of \c var_index must be the return value from the - previous call to \c reverse_next. It is not modified. - */ - - void reverse_cskip( - OpCode& op, const addr_t*& op_arg, size_t& op_index, size_t& var_index) - { using CppAD::NumRes; - using CppAD::NumArg; - CPPAD_ASSERT_UNKNOWN( op_ == op ); - CPPAD_ASSERT_UNKNOWN( op_arg == op_arg_ ); - CPPAD_ASSERT_UNKNOWN( op_index == op_index_ ); - CPPAD_ASSERT_UNKNOWN( var_index == var_index_ ); - - CPPAD_ASSERT_UNKNOWN( op == CSkipOp ); - CPPAD_ASSERT_UNKNOWN( NumArg(CSkipOp) == 0 ); - /* - The variables that need fixing are op_arg_ and op_arg. Currently, - op_arg points to the last arugment for the previous operator. - */ - // last argument for this cskip operation - --op_arg; - // first argument for this cskip operation - op_arg = op_arg_ -= (op_arg[0] + 7); - - CPPAD_ASSERT_UNKNOWN( - op_arg[4] + op_arg[5] == op_arg[ 6 + op_arg[4] + op_arg[5] ] - ); - CPPAD_ASSERT_UNKNOWN( op_index_ < op_rec_.size() ); - CPPAD_ASSERT_UNKNOWN( op_arg_rec_.data() <= op_arg_ ); - CPPAD_ASSERT_UNKNOWN( var_index_ < num_var_rec_ ); - } - -}; - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/pod_vector.hpp b/ct_core/include/ct/external/cppad/local/pod_vector.hpp deleted file mode 100644 index ed97617a8..000000000 --- a/ct_core/include/ct/external/cppad/local/pod_vector.hpp +++ /dev/null @@ -1,293 +0,0 @@ -// $Id: pod_vector.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_POD_VECTOR_HPP -# define CPPAD_POD_VECTOR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# if CPPAD_CSTDINT_HAS_8_TO_64 -# include -# endif -# include -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file pod_vector.hpp -File used to define pod_vector class -*/ - -/* -A list of which Types pod_vector consideres to be plain old data -*/ -/// default value is false -template inline bool is_pod(void) { return false; } -/// system pod types so far: -template <> inline bool is_pod(void) { return true; } -template <> inline bool is_pod(void) { return true; } -template <> inline bool is_pod(void) { return true; } -# if CPPAD_CSTDINT_HAS_8_TO_64 -template <> inline bool is_pod(void) { return true; } -template <> inline bool is_pod(void) { return true; } -template <> inline bool is_pod(void) { return true; } -template <> inline bool is_pod(void) { return true; } -// -template <> inline bool is_pod(void) { return true; } -template <> inline bool is_pod(void) { return true; } -template <> inline bool is_pod(void) { return true; } -template <> inline bool is_pod(void) { return true; } -# else // CPPAD_CSTDINT_HAS_8_TO_64 -template <> inline bool is_pod(void) { return true; } -template <> inline bool is_pod(void) { return true; } -template <> inline bool is_pod(void) { return true; } -// -template <> inline bool is_pod(void) { return true; } -template <> inline bool is_pod(void) { return true; } -template <> inline bool is_pod(void) { return true; } -# if CPPAD_SIZE_T_NOT_UNSIGNED_INT -template <> inline bool is_pod(void) { return true; } -# endif -# endif // CPPAD_CSTDINT_HAS_8_TO_64 - -/// CppAD pod types so far: -template <> inline bool is_pod(void) { return true; } - -// --------------------------------------------------------------------------- -/*! -A vector class with Type element that does not use element constructors -or destructors when Type is Plain Old Data (pod). -*/ -template -class pod_vector { -private: - /// maximum number of elements that should ever be in this vector - size_t max_length_; - /// number of elements currently in this vector - size_t length_; - /// maximum number of Type elements current allocation can hold - size_t capacity_; - /// pointer to the first type elements - /// (not defined and should not be used when capacity_ = 0) - Type *data_; - /// do not use the copy constructor - explicit pod_vector(const pod_vector& ) - { CPPAD_ASSERT_UNKNOWN(false); } -public: - /// Constructors set capacity, length, and data to zero. - /// - /// \param max_length - /// value for maximum number of elements in this vector. - inline pod_vector( - size_t max_length = std::numeric_limits::max() - ) - : max_length_(max_length), length_(0), capacity_(0), data_(CPPAD_NULL) - { } - // ---------------------------------------------------------------------- - /// Destructor: returns allocated memory to \c thread_alloc; - /// see \c extend. If this is not plain old data, - /// the destructor for each element is called. - ~pod_vector(void) - { if( capacity_ > 0 ) - { void* v_ptr = reinterpret_cast( data_ ); - if( ! is_pod() ) - { // call destructor for each element - size_t i; - for(i = 0; i < capacity_; i++) - (data_ + i)->~Type(); - } - thread_alloc::return_memory(v_ptr); - } - } - // ---------------------------------------------------------------------- - /// current number of elements in this vector. - inline size_t size(void) const - { return length_; } - /// current capacity (amount of allocated storage) for this vector. - inline size_t capacity(void) const - { return capacity_; } - /// current data pointer, no longer valid after any of the following: - /// extend, erase, operator=, and ~pod_vector. - /// Take extreem care when using this function. - inline Type* data(void) - { return data_; } - /// const version of \c data pointer - inline const Type* data(void) const - { return data_; } - // ---------------------------------------------------------------------- - /*! - Increase the number of elements the end of this vector. - - \param n - is the number of elements to add to end of this vector. - - \return - is the number of elements in the vector before \c extend was extended. - - - If \c Type is plain old data, new elements are not initialized; - i.e., their constructor is not called. Otherwise, the constructor - is called for each new element. - - - This is the only routine that allocates memory for \c pod_vector. - and it uses thread_alloc for this allocation, hence this determines - which thread corresponds to this vector (when in parallel mode). - - - If the resulting length of the vector would be more than \c max_length_, - and \c NDEBUG is not defined, a CPPAD_ASSERT is generated. - */ - inline size_t extend(size_t n) - { size_t old_length = length_; - length_ += n; - CPPAD_ASSERT_KNOWN( - length_ <= max_length_ , - "pod_vector.hpp: attempt to create to large a vector.\n" - "If Type is CPPAD_TYPE_ADDR_TYPE, tape is too long for Type." - ); - // check if we can use current memory - if( capacity_ >= length_ ) - return old_length; - - // save more old information - size_t old_capacity = capacity_; - Type* old_data = data_; - - // get new memory and set capacity - size_t length_bytes = length_ * sizeof(Type); - size_t capacity_bytes; - void* v_ptr = thread_alloc::get_memory(length_bytes, capacity_bytes); - capacity_ = capacity_bytes / sizeof(Type); - data_ = reinterpret_cast(v_ptr); - CPPAD_ASSERT_UNKNOWN( length_ <= capacity_ ); - - size_t i; - if( ! is_pod() ) - { // call constructor for each new element - for(i = 0; i < capacity_; i++) - new(data_ + i) Type(); - } - - // copy old data to new data - for(i = 0; i < old_length; i++) - data_[i] = old_data[i]; - - // return old memory to available pool - if( old_capacity > 0 ) - { v_ptr = reinterpret_cast( old_data ); - if( ! is_pod() ) - { for(i = 0; i < old_capacity; i++) - (old_data + i)->~Type(); - } - thread_alloc::return_memory(v_ptr); - } - - // return value for extend(n) is the old length - return old_length; - } - // ---------------------------------------------------------------------- - /// non-constant element access; i.e., we can change this element value - Type& operator[]( - /// element index, must be less than length - size_t i - ) - { CPPAD_ASSERT_UNKNOWN( i < length_ ); - return data_[i]; - } - // ---------------------------------------------------------------------- - /// constant element access; i.e., we cannot change this element value - const Type& operator[]( - /// element index, must be less than length - size_t i - ) const - { CPPAD_ASSERT_UNKNOWN( i < length_ ); - return data_[i]; - } - // ---------------------------------------------------------------------- - /*! - Remove all the elements from this vector but leave the capacity - and data pointer as is. - - */ - void erase(void) - { length_ = 0; - return; - } - // ---------------------------------------------------------------------- - /*! - Remove all the elements from this vector and delete its memory. - */ - void free(void) - { if( capacity_ > 0 ) - { void* v_ptr = reinterpret_cast( data_ ); - if( ! is_pod() ) - { // call destructor for each element - size_t i; - for(i = 0; i < capacity_; i++) - (data_ + i)->~Type(); - } - thread_alloc::return_memory(v_ptr); - } - data_ = CPPAD_NULL; - capacity_ = 0; - length_ = 0; - } - /// vector assignment operator - /// If the resulting length of the vector would be more than - /// \c max_length_, and \c NDEBUG is not defined, - /// a CPPAD_ASSERT is generated. - void operator=( - /// right hand size of the assingment operation - const pod_vector& x - ) - { size_t i; - - if( x.length_ <= capacity_ ) - { // use existing allocation for this vector - length_ = x.length_; - CPPAD_ASSERT_KNOWN( - length_ <= max_length_ , - "pod_vector.hpp: attempt to create to large a vector.\n" - "If Type is CPPAD_TYPE_ADDR_TYPE, tape long for Type." - ); - } - else - { // free old memory and get new memory of sufficient length - if( capacity_ > 0 ) - { void* v_ptr = reinterpret_cast( data_ ); - if( ! is_pod() ) - { // call destructor for each element - for(i = 0; i < capacity_; i++) - (data_ + i)->~Type(); - } - thread_alloc::return_memory(v_ptr); - } - length_ = capacity_ = 0; - extend( x.length_ ); - } - CPPAD_ASSERT_UNKNOWN( length_ == x.length_ ); - for(i = 0; i < length_; i++) - { data_[i] = x.data_[i]; } - } - /*! - Swap all properties of this vector with another. - - \param other - is the other vector that we are swapping this vector with. - */ - void swap(pod_vector& other) - { std::swap(capacity_, other.capacity_); - std::swap(length_, other.length_); - std::swap(data_, other.data_); - } -}; - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/pow.hpp b/ct_core/include/ct/external/cppad/local/pow.hpp deleted file mode 100644 index 00312a8ea..000000000 --- a/ct_core/include/ct/external/cppad/local/pow.hpp +++ /dev/null @@ -1,258 +0,0 @@ -// $Id: pow.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_POW_HPP -# define CPPAD_POW_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin pow$$ -$spell - Vec - std - namespace - CppAD - const -$$ - - -$section The AD Power Function$$ -$mindex pow exponent$$ - -$head Syntax$$ -$icode%z% = pow(%x%, %y%)%$$ - -$head See Also$$ -$cref pow_int$$ - - -$head Purpose$$ -Determines the value of the power function which is defined by -$latex \[ - {\rm pow} (x, y) = x^y -\] $$ -This version of the $code pow$$ function may use -logarithms and exponentiation to compute derivatives. -This will not work if $icode x$$ is less than or equal zero. -If the value of $icode y$$ is an integer, -the $cref pow_int$$ function is used to compute this value -using only multiplication (and division if $icode y$$ is negative). -(This will work even if $icode x$$ is less than or equal zero.) - -$head x$$ -The argument $icode x$$ has one of the following prototypes -$codei% - const %Base%& %x% - const AD<%Base%>& %x% - const VecAD<%Base%>::reference& %x% -%$$ - -$head y$$ -The argument $icode y$$ has one of the following prototypes -$codei% - const %Base%& %y% - const AD<%Base%>& %y% - const VecAD<%Base%>::reference& %y% -%$$ - -$head z$$ -If both $icode x$$ and $icode y$$ are $icode Base$$ objects, -the result $icode z$$ is also a $icode Base$$ object. -Otherwise, it has prototype -$codei% - AD<%Base%> %z% -%$$ - -$head Operation Sequence$$ -This is an AD of $icode Base$$ -$cref/atomic operation/glossary/Operation/Atomic/$$ -and hence is part of the current -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Example$$ -$children% - example/pow.cpp -%$$ -The file -$cref pow.cpp$$ -is an examples and tests of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -// case where x and y are AD ----------------------------------------- -template AD -pow(const AD& x, const AD& y) -{ - // compute the Base part - AD result; - result.value_ = pow(x.value_, y.value_); - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - // check if there is a recording in progress - ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return result; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_x = x.tape_id_ == tape_id; - bool var_y = y.tape_id_ == tape_id; - - if( var_x ) - { if( var_y ) - { // result = variable^variable - CPPAD_ASSERT_UNKNOWN( NumRes(PowvvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumArg(PowvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(x.taddr_, y.taddr_); - - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(PowvvOp); - - // make result a variable - result.tape_id_ = tape_id; - } - else if( IdenticalZero( y.value_ ) ) - { // result = variable^0 - } - else - { // result = variable^parameter - CPPAD_ASSERT_UNKNOWN( NumRes(PowvpOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumArg(PowvpOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(y.value_); - tape->Rec_.PutArg(x.taddr_, p); - - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(PowvpOp); - - // make result a variable - result.tape_id_ = tape_id; - } - } - else if( var_y ) - { if( IdenticalZero(x.value_) ) - { // result = 0^variable - } - else - { // result = parameter^variable - CPPAD_ASSERT_UNKNOWN( NumRes(PowpvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumArg(PowpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(x.value_); - tape->Rec_.PutArg(p, y.taddr_); - - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(PowpvOp); - - // make result a variable - result.tape_id_ = tape_id; - } - } - return result; -} -// ========================================================================= -// Fold operations in same way as CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR(Op) -// ------------------------------------------------------------------------- -// Operations with VecAD_reference and AD only - -template AD -pow(const AD& x, const VecAD_reference& y) -{ return pow(x, y.ADBase()); } - -template AD -pow(const VecAD_reference& x, const VecAD_reference& y) -{ return pow(x.ADBase(), y.ADBase()); } - -template AD -pow(const VecAD_reference& x, const AD& y) -{ return pow(x.ADBase(), y); } -// ------------------------------------------------------------------------- -// Operations with Base - -template AD -pow(const Base& x, const AD& y) -{ return pow(AD(x), y); } - -template AD -pow(const Base& x, const VecAD_reference& y) -{ return pow(AD(x), y.ADBase()); } - -template AD -pow(const AD& x, const Base& y) -{ return pow(x, AD(y)); } - -template AD -pow(const VecAD_reference& x, const Base& y) -{ return pow(x.ADBase(), AD(y)); } -// ------------------------------------------------------------------------- -// Operations with double - -template AD -pow(const double& x, const AD& y) -{ return pow(AD(x), y); } - -template AD -pow(const double& x, const VecAD_reference& y) -{ return pow(AD(x), y.ADBase()); } - -template AD -pow(const AD& x, const double& y) -{ return pow(x, AD(y)); } - -template AD -pow(const VecAD_reference& x, const double& y) -{ return pow(x.ADBase(), AD(y)); } -// ------------------------------------------------------------------------- -// Special case to avoid ambuigity when Base is double - -inline AD -pow(const double& x, const AD& y) -{ return pow(AD(x), y); } - -inline AD -pow(const double& x, const VecAD_reference& y) -{ return pow(AD(x), y.ADBase()); } - -inline AD -pow(const AD& x, const double& y) -{ return pow(x, AD(y)); } - -inline AD -pow(const VecAD_reference& x, const double& y) -{ return pow(x.ADBase(), AD(y)); } - -// ========================================================================= -// Fold operations for the cases where x is an int, -// but let cppad/pow_int.hpp handle the cases where y is an int. -// ------------------------------------------------------------------------- -template AD pow -(const int& x, const VecAD_reference& y) -{ return pow(AD(x), y.ADBase()); } - -template AD pow -(const int& x, const AD& y) -{ return pow(AD(x), y); } - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/pow_op.hpp b/ct_core/include/ct/external/cppad/local/pow_op.hpp deleted file mode 100644 index 62fc582c3..000000000 --- a/ct_core/include/ct/external/cppad/local/pow_op.hpp +++ /dev/null @@ -1,633 +0,0 @@ -// $Id: pow_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_POW_OP_HPP -# define CPPAD_POW_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file pow_op.hpp -Forward and reverse mode calculations for z = pow(x, y). -*/ - -// --------------------------- Powvv ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = PowvvOp. - -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_pow_op -*/ - -template -inline void forward_powvv_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // convert from final result to first result - i_z -= 2; // 2 = NumRes(PowvvOp) - 1; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(PowvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(PowvvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // z_0 = log(x) - forward_log_op(p, q, i_z, arg[0], cap_order, taylor); - - // z_1 = z_0 * y - addr_t adr[2]; - adr[0] = i_z; - adr[1] = arg[1]; - forward_mulvv_op(p, q, i_z+1, adr, parameter, cap_order, taylor); - - // z_2 = exp(z_1) - // final result for zero order case is exactly the same as for Base - if( p == 0 ) - { // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - Base* z_2 = taylor + (i_z+2) * cap_order; - - z_2[0] = pow(x[0], y[0]); - p++; - } - if( p <= q ) - forward_exp_op(p, q, i_z+2, i_z+1, cap_order, taylor); -} -/*! -Multiple directions forward mode Taylor coefficients for op = PowvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = pow(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a variable and y is a parameter. - -\copydetails forward_pow_op_dir -*/ - -template -inline void forward_powvv_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // convert from final result to first result - i_z -= 2; // 2 = NumRes(PowvvOp) - 1 - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(PowvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(PowvvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // z_0 = log(x) - forward_log_op_dir(q, r, i_z, arg[0], cap_order, taylor); - - // z_1 = y * z_0 - addr_t adr[2]; - adr[0] = i_z; - adr[1] = arg[1]; - forward_mulvv_op_dir(q, r, i_z+1, adr, parameter, cap_order, taylor); - - // z_2 = exp(z_1) - forward_exp_op_dir(q, r, i_z+2, i_z+1, cap_order, taylor); -} -/*! -Compute zero order forward mode Taylor coefficients for result of op = PowvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = pow(x, y) -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_pow_op_0 -*/ - -template -inline void forward_powvv_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // convert from final result to first result - i_z -= 2; // NumRes(PowvvOp) - 1; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(PowvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(PowvvOp) == 3 ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - Base* z_0 = taylor + i_z * cap_order; - Base* z_1 = z_0 + cap_order; - Base* z_2 = z_1 + cap_order; - - z_0[0] = log( x[0] ); - z_1[0] = z_0[0] * y[0]; - z_2[0] = pow(x[0], y[0]); - -} - -/*! -Compute reverse mode partial derivatives for result of op = PowvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = pow(x, y) -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails reverse_pow_op -*/ - -template -inline void reverse_powvv_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // convert from final result to first result - i_z -= 2; // NumRes(PowvvOp) - 1; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(PowvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(PowvvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // z_2 = exp(z_1) - reverse_exp_op( - d, i_z+2, i_z+1, cap_order, taylor, nc_partial, partial - ); - - // z_1 = z_0 * y - addr_t adr[2]; - adr[0] = i_z; - adr[1] = arg[1]; - reverse_mulvv_op( - d, i_z+1, adr, parameter, cap_order, taylor, nc_partial, partial - ); - - // z_0 = log(x) - reverse_log_op( - d, i_z, arg[0], cap_order, taylor, nc_partial, partial - ); -} - -// --------------------------- Powpv ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = PowpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = pow(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_pow_op -*/ - -template -inline void forward_powpv_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // convert from final result to first result - i_z -= 2; // 2 = NumRes(PowpvOp) - 1; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(PowpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(PowpvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to arguments and result - Base* z_0 = taylor + i_z * cap_order; - - // z_0 = log(x) - Base x = parameter[ arg[0] ]; - size_t d; - for(d = p; d <= q; d++) - { if( d == 0 ) - z_0[d] = log(x); - else z_0[d] = Base(0); - } - - // z_1 = z_0 * y - addr_t adr[2]; - // offset of z_i in taylor (as if it were a parameter); i.e., log(x) - adr[0] = i_z * cap_order; - // offset of y in taylor (as a variable) - adr[1] = arg[1]; - - // Trick: use taylor both for the parameter vector and variable values - forward_mulpv_op(p, q, i_z+1, adr, taylor, cap_order, taylor); - - // z_2 = exp(z_1) - // zero order case exactly same as Base type operation - if( p == 0 ) - { Base* y = taylor + arg[1] * cap_order; - Base* z_2 = taylor + (i_z+2) * cap_order; - z_2[0] = pow(x, y[0]); - p++; - } - if( p <= q ) - forward_exp_op(p, q, i_z+2, i_z+1, cap_order, taylor); -} -/*! -Multiple directions forward mode Taylor coefficients for op = PowpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = pow(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_pow_op_dir -*/ - -template -inline void forward_powpv_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // convert from final result to first result - i_z -= 2; // 2 = NumRes(PowpvOp) - 1; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(PowpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(PowpvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to arguments and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* z_0 = taylor + i_z * num_taylor_per_var; - - // z_0 = log(x) - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - z_0[m+ell] = Base(0); - - // z_1 = z_0 * y - addr_t adr[2]; - // offset of z_0 in taylor (as if it were a parameter); i.e., log(x) - adr[0] = i_z * num_taylor_per_var; - // ofset of y in taylor (as a variable) - adr[1] = arg[1]; - - // Trick: use taylor both for the parameter vector and variable values - forward_mulpv_op_dir(q, r, i_z+1, adr, taylor, cap_order, taylor); - - // z_2 = exp(z_1) - forward_exp_op_dir(q, r, i_z+2, i_z+1, cap_order, taylor); -} -/*! -Compute zero order forward mode Taylor coefficient for result of op = PowpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = pow(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_pow_op_0 -*/ - -template -inline void forward_powpv_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // convert from final result to first result - i_z -= 2; // NumRes(PowpvOp) - 1; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(PowpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(PowpvOp) == 3 ); - - // Paraemter value - Base x = parameter[ arg[0] ]; - - // Taylor coefficients corresponding to arguments and result - Base* y = taylor + arg[1] * cap_order; - Base* z_0 = taylor + i_z * cap_order; - Base* z_1 = z_0 + cap_order; - Base* z_2 = z_1 + cap_order; - - // z_0 = log(x) - z_0[0] = log(x); - - // z_1 = z_0 * y - z_1[0] = z_0[0] * y[0]; - - // z_2 = exp(z_1) - // zero order case exactly same as Base type operation - z_2[0] = pow(x, y[0]); -} - -/*! -Compute reverse mode partial derivative for result of op = PowpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = pow(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails reverse_pow_op -*/ - -template -inline void reverse_powpv_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // convert from final result to first result - i_z -= 2; // NumRes(PowpvOp) - 1; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(PowvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(PowvvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // z_2 = exp(z_1) - reverse_exp_op( - d, i_z+2, i_z+1, cap_order, taylor, nc_partial, partial - ); - - // z_1 = z_0 * y - addr_t adr[2]; - adr[0] = i_z * cap_order; // offset of z_0[0] in taylor - adr[1] = arg[1]; // index of y in taylor and partial - // use taylor both for parameter and variable values - reverse_mulpv_op( - d, i_z+1, adr, taylor, cap_order, taylor, nc_partial, partial - ); - - // z_0 = log(x) - // x is a parameter -} - -// --------------------------- Powvp ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = PowvpOp. - -The C++ source code corresponding to this operation is -\verbatim - z = pow(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a variable and y is a parameter. - -\copydetails forward_pow_op -*/ - -template -inline void forward_powvp_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // convert from final result to first result - i_z -= 2; // 2 = NumRes(PowvpOp) - 1 - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(PowvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(PowvpOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // z_0 = log(x) - forward_log_op(p, q, i_z, arg[0], cap_order, taylor); - - // z_1 = y * z_0 - addr_t adr[2]; - adr[0] = arg[1]; - adr[1] = i_z; - forward_mulpv_op(p, q, i_z+1, adr, parameter, cap_order, taylor); - - // z_2 = exp(z_1) - // zero order case exactly same as Base type operation - if( p == 0 ) - { Base* z_2 = taylor + (i_z+2) * cap_order; - Base* x = taylor + arg[0] * cap_order; - Base y = parameter[ arg[1] ]; - z_2[0] = pow(x[0], y); - p++; - } - if( p <= q ) - forward_exp_op(p, q, i_z+2, i_z+1, cap_order, taylor); -} -/*! -Multiple directions forward mode Taylor coefficients for op = PowvpOp. - -The C++ source code corresponding to this operation is -\verbatim - z = pow(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a variable and y is a parameter. - -\copydetails forward_pow_op_dir -*/ - -template -inline void forward_powvp_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // convert from final result to first result - i_z -= 2; // 2 = NumRes(PowvpOp) - 1 - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(PowvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(PowvpOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // z_0 = log(x) - forward_log_op_dir(q, r, i_z, arg[0], cap_order, taylor); - - // z_1 = y * z_0 - addr_t adr[2]; - adr[0] = arg[1]; - adr[1] = i_z; - forward_mulpv_op_dir(q, r, i_z+1, adr, parameter, cap_order, taylor); - - // z_2 = exp(z_1) - forward_exp_op_dir(q, r, i_z+2, i_z+1, cap_order, taylor); -} - -/*! -Compute zero order forward mode Taylor coefficients for result of op = PowvpOp. - -The C++ source code corresponding to this operation is -\verbatim - z = pow(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a variable and y is a parameter. - -\copydetails forward_pow_op_0 -*/ - -template -inline void forward_powvp_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // convert from final result to first result - i_z -= 2; // NumRes(PowvpOp) - 1; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(PowvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(PowvpOp) == 3 ); - - // Paraemter value - Base y = parameter[ arg[1] ]; - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* z_0 = taylor + i_z * cap_order; - Base* z_1 = z_0 + cap_order; - Base* z_2 = z_1 + cap_order; - - // z_0 = log(x) - z_0[0] = log(x[0]); - - // z_1 = z_0 * y - z_1[0] = z_0[0] * y; - - // z_2 = exp(z_1) - // zero order case exactly same as Base type operation - z_2[0] = pow(x[0], y); -} - -/*! -Compute reverse mode partial derivative for result of op = PowvpOp. - -The C++ source code corresponding to this operation is -\verbatim - z = pow(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a variable and y is a parameter. - -\copydetails reverse_pow_op -*/ - -template -inline void reverse_powvp_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // convert from final result to first result - i_z -= 2; // NumRes(PowvpOp) - 1; - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(PowvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(PowvpOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // z_2 = exp(z_1) - reverse_exp_op( - d, i_z+2, i_z+1, cap_order, taylor, nc_partial, partial - ); - - // z_1 = y * z_0 - addr_t adr[2]; - adr[0] = arg[1]; - adr[1] = i_z; - reverse_mulpv_op( - d, i_z+1, adr, parameter, cap_order, taylor, nc_partial, partial - ); - - // z_0 = log(x) - reverse_log_op( - d, i_z, arg[0], cap_order, taylor, nc_partial, partial - ); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/print_for.hpp b/ct_core/include/ct/external/cppad/local/print_for.hpp deleted file mode 100644 index 16f6434ef..000000000 --- a/ct_core/include/ct/external/cppad/local/print_for.hpp +++ /dev/null @@ -1,216 +0,0 @@ -// $Id: print_for.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_PRINT_FOR_HPP -# define CPPAD_PRINT_FOR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin PrintFor$$ -$spell - pos - var - VecAD - std - cout - const -$$ - - -$section Printing AD Values During Forward Mode$$ -$mindex print text output debug$$ - -$head Syntax$$ -$icode%f%.Forward(0, %x%) -%$$ -$codei%PrintFor(%before%, %var%) -%$$ -$codei%PrintFor(%pos%, %before%, %var%, %after%) -%$$ - -$head Purpose$$ -The $cref/zero order forward/forward_zero/$$ mode command -$codei% - %f%.Forward(0, %x%) -%$$ -assigns the -$cref/independent variable/glossary/Tape/Independent Variable/$$ vector -equal to $icode x$$. -It then computes a value for all of the dependent variables in the -$cref/operation sequence/glossary/Operation/Sequence/$$ corresponding -to $icode f$$. -Putting a $code PrintFor$$ in the operation sequence will -cause the value of $icode var$$, corresponding to $icode x$$, -to be printed during zero order forward operations. - -$head f.Forward(0, x)$$ -The objects $icode f$$, $icode x$$, and the purpose -for this operation, are documented in $cref Forward$$. - -$head pos$$ -If present, the argument $icode pos$$ has one of the following prototypes -$codei% - const AD<%Base%>& %pos% - const VecAD<%Base%>::reference& %pos% -%$$ -In this case -the text and $icode var$$ will be printed if and only if -$icode pos$$ is not greater than zero and a finite number. - -$head before$$ -The argument $icode before$$ has prototype -$codei% - const char* %before% -%$$ -This text is written to $code std::cout$$ before $icode var$$. - -$head var$$ -The argument $icode var$$ has one of the following prototypes -$codei% - const AD<%Base%>& %var% - const VecAD<%Base%>::reference& %var% -%$$ -The value of $icode var$$, that corresponds to $icode x$$, -is written to $code std::cout$$ during the execution of -$codei% - %f%.Forward(0, %x%) -%$$ -Note that $icode var$$ may be a -$cref/variable/glossary/Variable/$$ or -$cref/parameter/glossary/Parameter/$$. -(A parameters value does not depend on the value of -the independent variable vector $icode x$$.) - -$head after$$ -The argument $icode after$$ has prototype -$codei% - const char* %after% -%$$ -This text is written to $code std::cout$$ after $icode var$$. - -$head Discussion$$ -This is helpful for understanding why tape evaluations -have trouble. -For example, if one of the operations in $icode f$$ is -$codei%log(%var%)%$$ and $icode%var% <= 0%$$, -the corresponding result will be $cref nan$$. - -$head Alternative$$ -The $cref ad_output$$ section describes the normal -printing of values; i.e., printing when the corresponding -code is executed. - -$head Example$$ -$children% - print_for/print_for.cpp% - example/print_for.cpp -%$$ -The program -$cref print_for_cout.cpp$$ -is an example and test that prints to standard output. -The output of this program -states the conditions for passing and failing the test. -The function -$cref print_for_string.cpp$$ -is an example and test that prints to an standard string stream. -This function automatically check for correct output. - -$end ------------------------------------------------------------------------------- -*/ - -# include - -namespace CppAD { - template - void PrintFor(const AD& pos, - const char *before, const AD& var, const char* after) - { CPPAD_ASSERT_NARG_NRES(PriOp, 5, 0); - - // check for case where we are not recording operations - ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return; - - CPPAD_ASSERT_KNOWN( - std::strlen(before) <= 1000 , - "PrintFor: length of before is greater than 1000 characters" - ); - CPPAD_ASSERT_KNOWN( - std::strlen(after) <= 1000 , - "PrintFor: length of after is greater than 1000 characters" - ); - size_t ind0, ind1, ind2, ind3, ind4; - - // ind[0] = base 2 representation of the value [Var(pos), Var(var)] - ind0 = 0; - - // ind[1] = address for pos - if( Parameter(pos) ) - ind1 = tape->Rec_.PutPar(pos.value_); - else - { ind0 += 1; - ind1 = pos.taddr_; - } - - // ind[2] = address of before - ind2 = tape->Rec_.PutTxt(before); - - // ind[3] = address for var - if( Parameter(var) ) - ind3 = tape->Rec_.PutPar(var.value_); - else - { ind0 += 2; - ind3 = var.taddr_; - } - - // ind[4] = address of after - ind4 = tape->Rec_.PutTxt(after); - - // put the operator in the tape - tape->Rec_.PutArg(ind0, ind1, ind2, ind3, ind4); - tape->Rec_.PutOp(PriOp); - } - // Fold all other cases into the case above - template - void PrintFor(const char* before, const AD& var) - { PrintFor(AD(0), before, var, "" ); } - // - template - void PrintFor(const char* before, const VecAD_reference& var) - { PrintFor(AD(0), before, var.ADBase(), "" ); } - // - template - void PrintFor( - const VecAD_reference& pos , - const char *before , - const VecAD_reference& var , - const char *after ) - { PrintFor(pos.ADBase(), before, var.ADBase(), after); } - // - template - void PrintFor( - const VecAD_reference& pos , - const char *before , - const AD& var , - const char *after ) - { PrintFor(pos.ADBase(), before, var, after); } - // - template - void PrintFor( - const AD& pos , - const char *before , - const VecAD_reference& var , - const char *after ) - { PrintFor(pos, before, var.ADBase(), after); } -} - -# endif diff --git a/ct_core/include/ct/external/cppad/local/print_op.hpp b/ct_core/include/ct/external/cppad/local/print_op.hpp deleted file mode 100644 index 07492fa27..000000000 --- a/ct_core/include/ct/external/cppad/local/print_op.hpp +++ /dev/null @@ -1,148 +0,0 @@ -// $Id: print_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_PRINT_OP_HPP -# define CPPAD_PRINT_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -Print operation for parameters; i.e., op = PriOp. - -The C++ source code corresponding to this operation is -\verbatim - f.Forward(0, x) - PrintFor(before, var) - PrintFor(pos, before, var, after) -\endverbatim -The PrintFor call puts the print operation on the tape -and the print occurs during the zero order forward mode computation. - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base . - -\param s_out -the results are printed on this output stream. - -\param arg -\a arg[0] & 1 -\n -If this is zero, \a pos is a parameter. Otherwise it is a variable. -\n -\a arg[0] & 2 -\n -If this is zero, \a var is a parameter. Otherwise it is a variable. -\n -\n -\a arg[1] -\n -If \a pos is a parameter, parameter[arg[1]] is its value. -Othwise taylor[ arg[1] * cap_order + 0 ] is the zero -order Taylor coefficient for \a pos. -\n -\n -\a arg[2] -\n -index of the text to be printed before \a var -if \a pos is not a positive value. -\n -\n -\a arg[3] -\n -If \a var is a parameter, parameter[arg[3]] is its value. -Othwise taylor[ arg[3] * cap_order + 0 ] is the zero -order Taylor coefficient for \a var. -\n -\n -\a arg[4] -\n -index of the text to be printed after \a var -if \a pos is not a positive value. - -\param num_text -is the total number of text characters on the tape -(only used for error checking). - -\param text -\b Input: text[arg[1]] is the first character of the text -that will be printed. All the characters from there to (but not including) -the first '\\0' are printed. - -\param num_par -is the total number of values in the \a parameter vector - -\param parameter -Contains the value of parameters. - -\param cap_order -number of colums in the matrix containing all the Taylor coefficients. - -\param taylor -Contains the value of variables. - -\par Checked Assertions: -\li NumArg(PriOp) == 5 -\li NumRes(PriOp) == 0 -\li text != CPPAD_NULL -\li arg[1] < num_text -\li if \a pos is a parameter, arg[1] < num_par -\li if \a var is a parameter, arg[3] < num_par -*/ -template -inline void forward_pri_0( - std::ostream& s_out , - const addr_t* arg , - size_t num_text , - const char* text , - size_t num_par , - const Base* parameter , - size_t cap_order , - const Base* taylor ) -{ Base pos, var; - const char* before; - const char* after; - CPPAD_ASSERT_NARG_NRES(PriOp, 5, 0); - - // pos - if( arg[0] & 1 ) - { pos = taylor[ arg[1] * cap_order + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - pos = parameter[ arg[1] ]; - } - - // before - CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < num_text ); - before = text + arg[2]; - - // var - if( arg[0] & 2 ) - { var = taylor[ arg[3] * cap_order + 0 ]; - } - else - { CPPAD_ASSERT_UNKNOWN( size_t(arg[3]) < num_par ); - var = parameter[ arg[3] ]; - } - - // after - CPPAD_ASSERT_UNKNOWN( size_t(arg[4]) < num_text ); - after = text + arg[4]; - - if( ! GreaterThanZero( pos ) ) - s_out << before << var << after; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/prototype_op.hpp b/ct_core/include/ct/external/cppad/local/prototype_op.hpp deleted file mode 100644 index 15949f5b3..000000000 --- a/ct_core/include/ct/external/cppad/local/prototype_op.hpp +++ /dev/null @@ -1,1460 +0,0 @@ -// $Id: prototype_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_PROTOTYPE_OP_HPP -# define CPPAD_PROTOTYPE_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file prototype_op.hpp -Documentation for generic cases (these generic cases are never used). -*/ - -// ==================== Unary operators with one result ==================== - - -/*! -Prototype for forward mode unary operator with one result (not used). - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param p -lowest order of the Taylor coefficient that we are computing. - -\param q -highest order of the Taylor coefficient that we are computing. - -\param i_z -variable index corresponding to the result for this operation; -i.e. the row index in \a taylor corresponding to z. - -\param i_x -variable index corresponding to the argument for this operator; -i.e. the row index in \a taylor corresponding to x. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\param taylor -\b Input: taylor [ i_x * cap_order + k ], -for k = 0 , ... , q, -is the k-th order Taylor coefficient corresponding to x. -\n -\b Input: taylor [ i_z * cap_order + k ], -for k = 0 , ... , p-1, -is the k-th order Taylor coefficient corresponding to z. -\n -\b Output: taylor [ i_z * cap_order + k ], -for k = p , ... , q, -is the k-th order Taylor coefficient corresponding to z. - -\par Checked Assertions -\li NumArg(op) == 1 -\li NumRes(op) == 1 -\li q < cap_order -\li p <= q -*/ -template -inline void forward_unary1_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} - -/*! -Prototype for multiple direction forward mode unary operator with one result -(not used). - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param q -order of the Taylor coefficients that we are computing. - -\param r -number of directions for Taylor coefficients that we are computing. - -\param i_z -variable index corresponding to the last (primary) result for this operation; -i.e. the row index in \a taylor corresponding to z. -The auxillary result is called y has index \a i_z - 1. - -\param i_x -variable index corresponding to the argument for this operator; -i.e. the row index in \a taylor corresponding to x. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\par tpv -We use the notation -tpv = (cap_order-1) * r + 1 -which is the number of Taylor coefficients per variable - -\param taylor -\b Input: If x is a variable, -taylor [ arg[0] * tpv + 0 ], -is the zero order Taylor coefficient for all directions and -taylor [ arg[0] * tpv + (k-1)*r + ell + 1 ], -for k = 1 , ... , q, -ell = 0, ..., r-1, -is the k-th order Taylor coefficient -corresponding to x and the ell-th direction. -\n -\b Input: taylor [ i_z * tpv + 0 ], -is the zero order Taylor coefficient for all directions and -taylor [ i_z * tpv + (k-1)*r + ell + 1 ], -for k = 1 , ... , q-1, -ell = 0, ..., r-1, -is the k-th order Taylor coefficient -corresponding to z and the ell-th direction. -\n -\b Output: -taylor [ i_z * tpv + (q-1)*r + ell + 1], -ell = 0, ..., r-1, -is the q-th order Taylor coefficient -corresponding to z and the ell-th direction. - -\par Checked Assertions -\li NumArg(op) == 1 -\li NumRes(op) == 2 -\li i_x < i_z -\li 0 < q -\li q < cap_order -*/ -template -inline void forward_unary1_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} - -/*! -Prototype for zero order forward mode unary operator with one result (not used). -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base . - -\param i_z -variable index corresponding to the result for this operation; -i.e. the row index in \a taylor corresponding to z. - -\param i_x -variable index corresponding to the argument for this operator; -i.e. the row index in \a taylor corresponding to x. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\param taylor -\b Input: \a taylor [ \a i_x * \a cap_order + 0 ] -is the zero order Taylor coefficient corresponding to x. -\n -\b Output: \a taylor [ \a i_z * \a cap_order + 0 ] -is the zero order Taylor coefficient corresponding to z. - -\par Checked Assertions -\li NumArg(op) == 1 -\li NumRes(op) == 1 -\li \a i_x < \a i_z -\li \a 0 < \a cap_order -*/ -template -inline void forward_unary1_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} - -/*! -Prototype for reverse mode unary operator with one result (not used). - -This routine is given the partial derivatives of a function -G(z , x , w, u ... ) -and it uses them to compute the partial derivatives of -\verbatim - H( x , w , u , ... ) = G[ z(x) , x , w , u , ... ] -\endverbatim - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base . - -\param d -highest order Taylor coefficient that -we are computing the partial derivatives with respect to. - -\param i_z -variable index corresponding to the result for this operation; -i.e. the row index in \a taylor to z. - -\param i_x -variable index corresponding to the argument for this operation; -i.e. the row index in \a taylor corresponding to x. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\param taylor -\a taylor [ \a i_x * \a cap_order + k ] -for k = 0 , ... , \a d -is the k-th order Taylor coefficient corresponding to x. -\n -\a taylor [ \a i_z * \a cap_order + k ] -for k = 0 , ... , \a d -is the k-th order Taylor coefficient corresponding to z. - -\param nc_partial -number of colums in the matrix containing all the partial derivatives. - -\param partial -\b Input: \a partial [ \a i_x * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of G( z , x , w , u , ... ) with respect to -the k-th order Taylor coefficient for x. -\n -\b Input: \a partial [ \a i_z * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of G( z , x , w , u , ... ) with respect to -the k-th order Taylor coefficient for z. -\n -\b Output: \a partial [ \a i_x * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of H( x , w , u , ... ) with respect to -the k-th order Taylor coefficient for x. -\n -\b Output: \a partial [ \a i_z * \a nc_partial + k ] -for k = 0 , ... , \a d -may be used as work space; i.e., may change in an unspecified manner. - - -\par Checked Assumptions -\li NumArg(op) == 1 -\li NumRes(op) == 1 -\li \a i_x < \a i_z -\li \a d < \a cap_order -\li \a d < \a nc_partial -*/ -template -inline void reverse_unary1_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} - -// ==================== Unary operators with two results ==================== - -/*! -Prototype for forward mode unary operator with two results (not used). - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param p -lowest order of the Taylor coefficients that we are computing. - -\param q -highest order of the Taylor coefficients that we are computing. - -\param i_z -variable index corresponding to the last (primary) result for this operation; -i.e. the row index in \a taylor corresponding to z. -The auxillary result is called y has index \a i_z - 1. - -\param i_x -variable index corresponding to the argument for this operator; -i.e. the row index in \a taylor corresponding to x. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\param taylor -\b Input: taylor [ i_x * cap_order + k ] -for k = 0 , ... , q, -is the k-th order Taylor coefficient corresponding to x. -\n -\b Input: taylor [ i_z * cap_order + k ] -for k = 0 , ... , p - 1, -is the k-th order Taylor coefficient corresponding to z. -\n -\b Input: taylor [ ( i_z - 1) * cap_order + k ] -for k = 0 , ... , p-1, -is the k-th order Taylor coefficient corresponding to the auxillary result y. -\n -\b Output: taylor [ i_z * cap_order + k ], -for k = p , ... , q, -is the k-th order Taylor coefficient corresponding to z. -\n -\b Output: taylor [ ( i_z - 1 ) * cap_order + k ], -for k = p , ... , q, -is the k-th order Taylor coefficient corresponding to -the autillary result y. - -\par Checked Assertions -\li NumArg(op) == 1 -\li NumRes(op) == 2 -\li i_x + 1 < i_z -\li q < cap_order -\li p <= q -*/ -template -inline void forward_unary2_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} - -/*! -Prototype for multiple direction forward mode unary operator with two results -(not used). - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param q -order of the Taylor coefficients that we are computing. - -\param r -number of directions for Taylor coefficients that we are computing. - -\param i_z -variable index corresponding to the last (primary) result for this operation; -i.e. the row index in \a taylor corresponding to z. -The auxillary result is called y has index \a i_z - 1. - -\param i_x -variable index corresponding to the argument for this operator; -i.e. the row index in \a taylor corresponding to x. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\par tpv -We use the notation -tpv = (cap_order-1) * r + 1 -which is the number of Taylor coefficients per variable - -\param taylor -\b Input: taylor [ i_x * tpv + 0 ] -is the zero order Taylor coefficient for all directions and -taylor [ i_x * tpv + (k-1)*r + ell + 1 -for k = 1 , ... , q, -ell = 0 , ..., r-1, -is the k-th order Taylor coefficient -corresponding to x and the ell-th direction. -\n -\b Input: taylor [ i_z * tpv + 0 ], -is the zero order Taylor coefficient for all directions and -taylor [ i_z * tpv + (k-1)*r + ell + 1 ], -for k = 1 , ... , q-1, -ell = 0, ..., r-1, -is the k-th order Taylor coefficient -corresponding to z and the ell-th direction. -\n -\b Input: taylor [ (i_z-1) * tpv + 0 ], -is the zero order Taylor coefficient for all directions and -taylor [ (i_z-1) * tpv + (k-1)*r + ell + 1 ], -for k = 1 , ... , q-1, -ell = 0, ..., r-1, -is the k-th order Taylor coefficient -corresponding to the auxillary result y and the ell-th direction. -\n -\b Output: -taylor [ i_z * tpv + (q-1)*r + ell + 1], -ell = 0, ..., r-1, -is the q-th order Taylor coefficient -corresponding to z and the ell-th direction. - -\par Checked Assertions -\li NumArg(op) == 1 -\li NumRes(op) == 2 -\li i_x + 1 < i_z -\li 0 < q -\li q < cap_order -*/ -template -inline void forward_unary2_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} - -/*! -Prototype for zero order forward mode unary operator with two results (not used). -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base . - -\param i_z -variable index corresponding to the last (primary) result for this operation; -i.e. the row index in \a taylor corresponding to z. -The auxillary result is called y and has index \a i_z - 1. - -\param i_x -variable index corresponding to the argument for this operator; -i.e. the row index in \a taylor corresponding to x. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\param taylor -\b Input: \a taylor [ \a i_x * \a cap_order + 0 ] -is the zero order Taylor coefficient corresponding to x. -\n -\b Output: \a taylor [ \a i_z * \a cap_order + 0 ] -is the zero order Taylor coefficient corresponding to z. -\n -\b Output: \a taylor [ ( \a i_z - 1 ) * \a cap_order + j ] -is the j-th order Taylor coefficient corresponding to -the autillary result y. - -\par Checked Assertions -\li NumArg(op) == 1 -\li NumRes(op) == 2 -\li \a i_x + 1 < \a i_z -\li \a j < \a cap_order -*/ -template -inline void forward_unary2_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} - -/*! -Prototype for reverse mode unary operator with two results (not used). - -This routine is given the partial derivatives of a function -G( z , y , x , w , ... ) -and it uses them to compute the partial derivatives of -\verbatim - H( x , w , u , ... ) = G[ z(x) , y(x), x , w , u , ... ] -\endverbatim - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base . - -\param d -highest order Taylor coefficient that -we are computing the partial derivatives with respect to. - -\param i_z -variable index corresponding to the last (primary) result for this operation; -i.e. the row index in \a taylor to z. -The auxillary result is called y and has index \a i_z - 1. - -\param i_x -variable index corresponding to the argument for this operation; -i.e. the row index in \a taylor corresponding to x. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\param taylor -\a taylor [ \a i_x * \a cap_order + k ] -for k = 0 , ... , \a d -is the k-th order Taylor coefficient corresponding to x. -\n -\a taylor [ \a i_z * \a cap_order + k ] -for k = 0 , ... , \a d -is the k-th order Taylor coefficient corresponding to z. -\n -\a taylor [ ( \a i_z - 1) * \a cap_order + k ] -for k = 0 , ... , \a d -is the k-th order Taylor coefficient corresponding to -the auxillary variable y. - -\param nc_partial -number of colums in the matrix containing all the partial derivatives. - -\param partial -\b Input: \a partial [ \a i_x * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of -G( z , y , x , w , u , ... ) -with respect to the k-th order Taylor coefficient for x. -\n -\b Input: \a partial [ \a i_z * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of G( z , y , x , w , u , ... ) with respect to -the k-th order Taylor coefficient for z. -\n -\b Input: \a partial [ ( \a i_z - 1) * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of G( z , x , w , u , ... ) with respect to -the k-th order Taylor coefficient for the auxillary variable y. -\n -\b Output: \a partial [ \a i_x * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of H( x , w , u , ... ) with respect to -the k-th order Taylor coefficient for x. -\n -\b Output: \a partial [ \a ( i_z - j ) * \a nc_partial + k ] -for j = 0 , 1 , and for k = 0 , ... , \a d -may be used as work space; i.e., may change in an unspecified manner. - - -\par Checked Assumptions -\li NumArg(op) == 1 -\li NumRes(op) == 2 -\li \a i_x + 1 < \a i_z -\li \a d < \a cap_order -\li \a d < \a nc_partial -*/ -template -inline void reverse_unary2_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} -// =================== Binary operators with one result ==================== - -/*! -Prototype forward mode x op y (not used) - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param p -lowest order of the Taylor coefficient that we are computing. - -\param q -highest order of the Taylor coefficient that we are computing. - -\param i_z -variable index corresponding to the result for this operation; -i.e. the row index in \a taylor corresponding to z. - -\param arg -\a arg[0] -index corresponding to the left operand for this operator; -i.e. the index corresponding to x. -\n -\a arg[1] -index corresponding to the right operand for this operator; -i.e. the index corresponding to y. - -\param parameter -If x is a parameter, \a parameter [ \a arg[0] ] -is the value corresponding to x. -\n -If y is a parameter, \a parameter [ \a arg[1] ] -is the value corresponding to y. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\param taylor -\b Input: If x is a variable, -taylor [ arg[0] * cap_order + k ], -for k = 0 , ... , q, -is the k-th order Taylor coefficient corresponding to x. -\n -\b Input: If y is a variable, -taylor [ arg[1] * cap_order + k ], -for k = 0 , ... , q, -is the k-th order Taylor coefficient corresponding to y. -\n -\b Input: taylor [ i_z * cap_order + k ], -for k = 0 , ... , p-1, -is the k-th order Taylor coefficient corresponding to z. -\n -\b Output: taylor [ i_z * cap_order + k ], -for k = p, ... , q, -is the k-th order Taylor coefficient corresponding to z. - -\par Checked Assertions -\li NumArg(op) == 2 -\li NumRes(op) == 1 -\li q < cap_order -\li p <= q -*/ -template -inline void forward_binary_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} - -/*! -Prototype multiple direction forward mode x op y (not used) - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param q -is the order of the Taylor coefficients that we are computing. - -\param r -number of directions for Taylor coefficients that we are computing - -\param i_z -variable index corresponding to the result for this operation; -i.e. the row index in \a taylor corresponding to z. - -\param arg -\a arg[0] -index corresponding to the left operand for this operator; -i.e. the index corresponding to x. -\n -\a arg[1] -index corresponding to the right operand for this operator; -i.e. the index corresponding to y. - -\param parameter -If x is a parameter, \a parameter [ \a arg[0] ] -is the value corresponding to x. -\n -If y is a parameter, \a parameter [ \a arg[1] ] -is the value corresponding to y. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\par tpv -We use the notation -tpv = (cap_order-1) * r + 1 -which is the number of Taylor coefficients per variable - -\param taylor -\b Input: If x is a variable, -taylor [ arg[0] * tpv + 0 ], -is the zero order Taylor coefficient for all directions and -taylor [ arg[0] * tpv + (k-1)*r + ell + 1 ], -for k = 1 , ... , q, -ell = 0, ..., r-1, -is the k-th order Taylor coefficient -corresponding to x and the ell-th direction. -\n -\b Input: If y is a variable, -taylor [ arg[1] * tpv + 0 ], -is the zero order Taylor coefficient for all directions and -taylor [ arg[1] * tpv + (k-1)*r + ell + 1 ], -for k = 1 , ... , q, -ell = 0, ..., r-1, -is the k-th order Taylor coefficient -corresponding to y and the ell-th direction. -\n -\b Input: taylor [ i_z * tpv + 0 ], -is the zero order Taylor coefficient for all directions and -taylor [ i_z * tpv + (k-1)*r + ell + 1 ], -for k = 1 , ... , q-1, -ell = 0, ..., r-1, -is the k-th order Taylor coefficient -corresponding to z and the ell-th direction. -\n -\b Output: -taylor [ i_z * tpv + (q-1)*r + ell + 1], -ell = 0, ..., r-1, -is the q-th order Taylor coefficient -corresponding to z and the ell-th direction. - -\par Checked Assertions -\li NumArg(op) == 2 -\li NumRes(op) == 1 -\li 0 < q < cap_order -*/ -template -inline void forward_binary_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} - - -/*! -Prototype zero order forward mode x op y (not used) - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param i_z -variable index corresponding to the result for this operation; -i.e. the row index in \a taylor corresponding to z. - -\param arg -\a arg[0] -index corresponding to the left operand for this operator; -i.e. the index corresponding to x. -\n -\a arg[1] -index corresponding to the right operand for this operator; -i.e. the index corresponding to y. - -\param parameter -If x is a parameter, \a parameter [ \a arg[0] ] -is the value corresponding to x. -\n -If y is a parameter, \a parameter [ \a arg[1] ] -is the value corresponding to y. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\param taylor -\b Input: If x is a variable, \a taylor [ \a arg[0] * \a cap_order + 0 ] -is the zero order Taylor coefficient corresponding to x. -\n -\b Input: If y is a variable, \a taylor [ \a arg[1] * \a cap_order + 0 ] -is the zero order Taylor coefficient corresponding to y. -\n -\b Output: \a taylor [ \a i_z * \a cap_order + 0 ] -is the zero order Taylor coefficient corresponding to z. - -\par Checked Assertions -\li NumArg(op) == 2 -\li NumRes(op) == 1 -*/ -template -inline void forward_binary_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} - -/*! -Prototype for reverse mode binary operator x op y (not used). - -This routine is given the partial derivatives of a function -G( z , y , x , w , ... ) -and it uses them to compute the partial derivatives of -\verbatim - H( y , x , w , u , ... ) = G[ z(x , y) , y , x , w , u , ... ] -\endverbatim - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base . - -\param d -highest order Taylor coefficient that -we are computing the partial derivatives with respect to. - -\param i_z -variable index corresponding to the result for this operation; -i.e. the row index in \a taylor corresponding to z. - -\param arg -\a arg[0] -index corresponding to the left operand for this operator; -i.e. the index corresponding to x. -\n -\a arg[1] -index corresponding to the right operand for this operator; -i.e. the index corresponding to y. - -\param parameter -If x is a parameter, \a parameter [ \a arg[0] ] -is the value corresponding to x. -\n -If y is a parameter, \a parameter [ \a arg[1] ] -is the value corresponding to y. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\param taylor -\a taylor [ \a i_z * \a cap_order + k ] -for k = 0 , ... , \a d -is the k-th order Taylor coefficient corresponding to z. -\n -If x is a variable, \a taylor [ \a arg[0] * \a cap_order + k ] -for k = 0 , ... , \a d -is the k-th order Taylor coefficient corresponding to x. -\n -If y is a variable, \a taylor [ \a arg[1] * \a cap_order + k ] -for k = 0 , ... , \a d -is the k-th order Taylor coefficient corresponding to y. - -\param nc_partial -number of colums in the matrix containing all the partial derivatives. - -\param partial -\b Input: \a partial [ \a i_z * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of -G( z , y , x , w , u , ... ) -with respect to the k-th order Taylor coefficient for z. -\n -\b Input: If x is a variable, \a partial [ \a arg[0] * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of G( z , y , x , w , u , ... ) with respect to -the k-th order Taylor coefficient for x. -\n -\b Input: If y is a variable, \a partial [ \a arg[1] * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of G( z , x , w , u , ... ) with respect to -the k-th order Taylor coefficient for the auxillary variable y. -\n -\b Output: If x is a variable, \a partial [ \a arg[0] * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of H( y , x , w , u , ... ) with respect to -the k-th order Taylor coefficient for x. -\n -\b Output: If y is a variable, \a partial [ \a arg[1] * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of H( y , x , w , u , ... ) with respect to -the k-th order Taylor coefficient for y. -\n -\b Output: \a partial [ \a i_z * \a nc_partial + k ] -for k = 0 , ... , \a d -may be used as work space; i.e., may change in an unspecified manner. - -\par Checked Assumptions -\li NumArg(op) == 2 -\li NumRes(op) == 1 -\li \a If x is a variable, arg[0] < \a i_z -\li \a If y is a variable, arg[1] < \a i_z -\li \a d < \a cap_order -\li \a d < \a nc_partial -*/ -template -inline void reverse_binary_op( - size_t d , - size_t i_z , - addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} -// ======================= Pow Function =================================== -/*! -Prototype for forward mode z = pow(x, y) (not used). - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param p -lowest order of the Taylor coefficient that we are computing. - -\param q -highest order of the Taylor coefficient that we are computing. - -\param i_z -variable index corresponding to the last (primary) result for this operation; -i.e. the row index in \a taylor corresponding to z. -Note that there are three results for this operation, -below they are referred to as z_0, z_1, z_2 and correspond to -\verbatim - z_0 = log(x) - z_1 = z0 * y - z_2 = exp(z1) -\endverbatim -It follows that the final result is equal to z; i.e., z = z_2 = pow(x, y). - -\param arg -\a arg[0] -index corresponding to the left operand for this operator; -i.e. the index corresponding to x. -\n -\a arg[1] -index corresponding to the right operand for this operator; -i.e. the index corresponding to y. - -\param parameter -If x is a parameter, \a parameter [ \a arg[0] ] -is the value corresponding to x. -\n -If y is a parameter, \a parameter [ \a arg[1] ] -is the value corresponding to y. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\param taylor -\b Input: If x is a variable, -taylor [ arg[0] * cap_order + k ] -for k = 0 , ... , q, -is the k-th order Taylor coefficient corresponding to x. -\n -\b Input: If y is a variable, -taylor [ arg[1] * cap_order + k ] -for k = 0 , ... , q -is the k-th order Taylor coefficient corresponding to y. -\n -\b Input: taylor [ (i_z-2+j) * cap_order + k ], -for j = 0, 1, 2 , for k = 0 , ... , p-1, -is the k-th order Taylor coefficient corresponding to z_j. -\n -\b Output: taylor [ (i_z-2+j) * cap_order + k ], -is the k-th order Taylor coefficient corresponding to z_j. - -\par Checked Assertions -\li NumArg(op) == 2 -\li NumRes(op) == 3 -\li If x is a variable, arg[0] < i_z - 2 -\li If y is a variable, arg[1] < i_z - 2 -\li q < cap_order -\li p <= q -*/ -template -inline void forward_pow_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} -/*! -Prototype for multiple direction forward mode z = pow(x, y) (not used). - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param q -order of the Taylor coefficient that we are computing. - -\param r -is the number of Taylor coefficient directions that we are computing - -\param i_z -variable index corresponding to the last (primary) result for this operation; -i.e. the row index in \a taylor corresponding to z. -Note that there are three results for this operation, -below they are referred to as z_0, z_1, z_2 and correspond to -\verbatim - z_0 = log(x) - z_1 = z0 * y - z_2 = exp(z1) -\endverbatim -It follows that the final result is equal to z; i.e., z = z_2 = pow(x, y). - -\param arg -\a arg[0] -index corresponding to the left operand for this operator; -i.e. the index corresponding to x. -\n -\a arg[1] -index corresponding to the right operand for this operator; -i.e. the index corresponding to y. - -\param parameter -If x is a parameter, \a parameter [ \a arg[0] ] -is the value corresponding to x. -\n -If y is a parameter, \a parameter [ \a arg[1] ] -is the value corresponding to y. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\par tpv -We use the notation -tpv = (cap_order-1) * r + 1 -which is the number of Taylor coefficients per variable - -\param taylor -\b Input: If x is a variable, -taylor [ arg[0] * tpv + 0 ] -is the zero order coefficient corresponding to x and -taylor [ arg[0] * tpv + (k-1)*r+1+ell ] -for k = 1 , ... , q, -ell = 0 , ... , r-1, -is the k-th order Taylor coefficient corresponding to x -for the ell-th direction. -\n -\n -\b Input: If y is a variable, -taylor [ arg[1] * tpv + 0 ] -is the zero order coefficient corresponding to y and -taylor [ arg[1] * tpv + (k-1)*r+1+ell ] -for k = 1 , ... , q, -ell = 0 , ... , r-1, -is the k-th order Taylor coefficient corresponding to y -for the ell-th direction. -\n -\n -\b Input: -taylor [ (i_z-2+j) * tpv + 0 ], -is the zero order coefficient corresponding to z_j and -taylor [ (i_z-2+j) * tpv + (k-1)*r+1+ell ], -for j = 0, 1, 2 , k = 0 , ... , q-1, ell = 0, ... , r-1, -is the k-th order Taylor coefficient corresponding to z_j -for the ell-th direction. -\n -\n -\b Output: -taylor [ (i_z-2+j) * tpv + (q-1)*r+1+ell ], -for j = 0, 1, 2 , ell = 0, ... , r-1, -is the q-th order Taylor coefficient corresponding to z_j -for the ell-th direction. - -\par Checked Assertions -\li NumArg(op) == 2 -\li NumRes(op) == 3 -\li If x is a variable, arg[0] < i_z - 2 -\li If y is a variable, arg[1] < i_z - 2 -\li 0 < q -\li q < cap_order -*/ -template -inline void forward_pow_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} -/*! -Prototype for zero order forward mode z = pow(x, y) (not used). - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param i_z -variable index corresponding to the last (primary) result for this operation; -i.e. the row index in \a taylor corresponding to z. -Note that there are three results for this operation, -below they are referred to as z_0, z_1, z_2 and correspond to -\verbatim - z_0 = log(x) - z_1 = z0 * y - z_2 = exp(z1) -\endverbatim -It follows that the final result is equal to z; i.e., z = z_2 = pow(x, y). - -\param arg -\a arg[0] -index corresponding to the left operand for this operator; -i.e. the index corresponding to x. -\n -\a arg[1] -index corresponding to the right operand for this operator; -i.e. the index corresponding to y. - -\param parameter -If x is a parameter, \a parameter [ \a arg[0] ] -is the value corresponding to x. -\n -If y is a parameter, \a parameter [ \a arg[1] ] -is the value corresponding to y. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\param taylor -\b Input: If x is a variable, \a taylor [ \a arg[0] * \a cap_order + 0 ] -is the zero order Taylor coefficient corresponding to x. -\n -\b Input: If y is a variable, \a taylor [ \a arg[1] * \a cap_order + 0 ] -is the k-th order Taylor coefficient corresponding to y. -\n -\b Output: \a taylor [ \a (i_z - 2 + j) * \a cap_order + 0 ] -is the zero order Taylor coefficient corresponding to z_j. - -\par Checked Assertions -\li NumArg(op) == 2 -\li NumRes(op) == 3 -\li If x is a variable, \a arg[0] < \a i_z - 2 -\li If y is a variable, \a arg[1] < \a i_z - 2 -*/ -template -inline void forward_pow_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} -/*! -Prototype for reverse mode z = pow(x, y) (not used). - -This routine is given the partial derivatives of a function -G( z , y , x , w , ... ) -and it uses them to compute the partial derivatives of -\verbatim - H( y , x , w , u , ... ) = G[ pow(x , y) , y , x , w , u , ... ] -\endverbatim - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base . - -\param d -highest order Taylor coefficient that -we are computing the partial derivatives with respect to. - -\param i_z -variable index corresponding to the last (primary) result for this operation; -i.e. the row index in \a taylor corresponding to z. -Note that there are three results for this operation, -below they are referred to as z_0, z_1, z_2 and correspond to -\verbatim - z_0 = log(x) - z_1 = z0 * y - z_2 = exp(z1) -\endverbatim -It follows that the final result is equal to z; i.e., z = z_2 = pow(x, y). - -\param arg -\a arg[0] -index corresponding to the left operand for this operator; -i.e. the index corresponding to x. -\n -\a arg[1] -index corresponding to the right operand for this operator; -i.e. the index corresponding to y. - -\param parameter -If x is a parameter, \a parameter [ \a arg[0] ] -is the value corresponding to x. -\n -If y is a parameter, \a parameter [ \a arg[1] ] -is the value corresponding to y. - -\param cap_order -maximum number of orders that will fit in the \c taylor array. - -\param taylor -\a taylor [ \a (i_z - 2 + j) * \a cap_order + k ] -for j = 0, 1, 2 and k = 0 , ... , \a d -is the k-th order Taylor coefficient corresponding to z_j. -\n -If x is a variable, \a taylor [ \a arg[0] * \a cap_order + k ] -for k = 0 , ... , \a d -is the k-th order Taylor coefficient corresponding to x. -\n -If y is a variable, \a taylor [ \a arg[1] * \a cap_order + k ] -for k = 0 , ... , \a d -is the k-th order Taylor coefficient corresponding to y. - -\param nc_partial -number of colums in the matrix containing all the partial derivatives. - -\param partial -\b Input: \a partial [ \a (i_z - 2 + j) * \a nc_partial + k ] -for j = 0, 1, 2, and k = 0 , ... , \a d -is the partial derivative of -G( z , y , x , w , u , ... ) -with respect to the k-th order Taylor coefficient for z_j. -\n -\b Input: If x is a variable, \a partial [ \a arg[0] * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of G( z , y , x , w , u , ... ) with respect to -the k-th order Taylor coefficient for x. -\n -\b Input: If y is a variable, \a partial [ \a arg[1] * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of G( z , x , w , u , ... ) with respect to -the k-th order Taylor coefficient for the auxillary variable y. -\n -\b Output: If x is a variable, \a partial [ \a arg[0] * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of H( y , x , w , u , ... ) with respect to -the k-th order Taylor coefficient for x. -\n -\b Output: If y is a variable, \a partial [ \a arg[1] * \a nc_partial + k ] -for k = 0 , ... , \a d -is the partial derivative of H( y , x , w , u , ... ) with respect to -the k-th order Taylor coefficient for y. -\n -\b Output: \a partial [ \a ( i_z - j ) * \a nc_partial + k ] -for j = 0 , 1 , 2 and for k = 0 , ... , \a d -may be used as work space; i.e., may change in an unspecified manner. - -\par Checked Assumptions -\li NumArg(op) == 2 -\li NumRes(op) == 3 -\li \a If x is a variable, arg[0] < \a i_z - 2 -\li \a If y is a variable, arg[1] < \a i_z - 2 -\li \a d < \a cap_order -\li \a d < \a nc_partial -*/ -template -inline void reverse_pow_op( - size_t d , - size_t i_z , - addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} - -// ==================== Sparsity Calculations ============================== -/*! -Prototype for reverse mode Hessian sparsity unary operators. - -This routine is given the forward mode Jacobian sparsity patterns for x. -It is also given the reverse mode dependence of G on z. -In addition, it is given the revese mode Hessian sparsity -for the quanity of interest G(z , y , ... ) -and it uses them to compute the sparsity patterns for -\verbatim - H( x , w , u , ... ) = G[ z(x) , x , w , u , ... ] -\endverbatim - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param i_z -variable index corresponding to the result for this operation; -i.e. the row index in sparsity corresponding to z. - -\param i_x -variable index corresponding to the argument for this operator; -i.e. the row index in sparsity corresponding to x. - -\param rev_jacobian -\a rev_jacobian[i_z] -is all false (true) if the Jacobian of G with respect to z must be zero -(may be non-zero). -\n -\n -\a rev_jacobian[i_x] -is all false (true) if the Jacobian with respect to x must be zero -(may be non-zero). -On input, it corresponds to the function G, -and on output it corresponds to the function H. - -\param for_jac_sparsity -The set with index \a i_x in for_jac_sparsity -is the forward mode Jacobian sparsity pattern for the variable x. - -\param rev_hes_sparsity -The set with index \a i_z in in \a rev_hes_sparsity -is the Hessian sparsity pattern for the fucntion G -where one of the partials derivative is with respect to z. -\n -\n -The set with index \a i_x in \a rev_hes_sparsity -is the Hessian sparsity pattern -where one of the partials derivative is with respect to x. -On input, it corresponds to the function G, -and on output it corresponds to the function H. - -\par Checked Assertions: -\li \a i_x < \a i_z -*/ - -template -inline void reverse_sparse_hessian_unary_op( - size_t i_z , - size_t i_x , - bool* rev_jacobian , - Vector_set& for_jac_sparsity , - Vector_set& rev_hes_sparsity ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} - -/*! -Prototype for reverse mode Hessian sparsity binary operators. - -This routine is given the sparsity patterns the Hessian -of a function G(z, y, x, ... ) -and it uses them to compute the sparsity patterns for the Hessian of -\verbatim - H( y, x, w , u , ... ) = G[ z(x,y) , y , x , w , u , ... ] -\endverbatim - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param i_z -variable index corresponding to the result for this operation; -i.e. the row index in sparsity corresponding to z. - -\param arg -\a arg[0] -variable index corresponding to the left operand for this operator; -i.e. the set with index \a arg[0] in \a var_sparsity -is the spasity pattern correspoding to x. -\n -\n arg[1] -variable index corresponding to the right operand for this operator; -i.e. the row index in sparsity patterns corresponding to y. - -\param jac_reverse -\a jac_reverse[i_z] -is false (true) if the Jacobian of G with respect to z is always zero -(may be non-zero). -\n -\n -\a jac_reverse[ \a arg[0] ] -is false (true) if the Jacobian with respect to x is always zero -(may be non-zero). -On input, it corresponds to the function G, -and on output it corresponds to the function H. -\n -\n -\a jac_reverse[ \a arg[1] ] -is false (true) if the Jacobian with respect to y is always zero -(may be non-zero). -On input, it corresponds to the function G, -and on output it corresponds to the function H. - -\param for_jac_sparsity -The set with index \a arg[0] in \a for_jac_sparsity for the -is the forward Jacobian sparsity pattern for x. -\n -\n -The set with index \a arg[1] in \a for_jac_sparsity -is the forward sparsity pattern for y. - -\param rev_hes_sparsity -The set wiht index \a i_x in \a rev_hes_sparsity -is the Hessian sparsity pattern for the function G -where one of the partial derivatives is with respect to z. -\n -\n -The set with index \a arg[0] in \a rev_hes_sparsity -is the Hessian sparsity pattern where one of the -partial derivatives is with respect to x. -On input, it corresponds to the function G, -and on output it correspondst to H. -\n -\n -The set with index \a arg[1] in \a rev_hes_sparsity -is the Hessian sparsity pattern where one of the -partial derivatives is with respect to y. -On input, it corresponds to the function G, -and on output it correspondst to H. - -\par Checked Assertions: -\li \a arg[0] < \a i_z -\li \a arg[1] < \a i_z -*/ -template -inline void reverse_sparse_hessian_binary_op( - size_t i_z , - const addr_t* arg , - bool* jac_reverse , - Vector_set& for_jac_sparsity , - Vector_set& rev_hes_sparsity ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/recorder.hpp b/ct_core/include/ct/external/cppad/local/recorder.hpp deleted file mode 100644 index 07adc330a..000000000 --- a/ct_core/include/ct/external/cppad/local/recorder.hpp +++ /dev/null @@ -1,587 +0,0 @@ -// $Id: recorder.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_RECORDER_HPP -# define CPPAD_RECORDER_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file recorder.hpp -File used to define the recorder class. -*/ - -/*! -Class used to store an operation sequence while it is being recorded -(the operation sequence is copied to the player class for playback). - -\tparam Base -This is an AD< \a Base > operation sequence recording; i.e., -it records operations of type AD< \a Base >. -*/ -template -class recorder { - friend class player; - -private: - /// operator index at which to abort recording with an error - /// (do not abort when zero) - size_t abort_op_index_; - - /// offset for this thread in the static hash table - const size_t thread_offset_; - - /// Number of variables in the recording. - size_t num_var_rec_; - - /// Number vecad load operations (LdpOp or LdvOp) currently in recording. - size_t num_load_op_rec_; - - /// The operators in the recording. - pod_vector op_rec_; - - /// The VecAD indices in the recording. - pod_vector vecad_ind_rec_; - - /// The argument indices in the recording - pod_vector op_arg_rec_; - - /// The parameters in the recording. - /// Note that Base may not be plain old data, so use false in consructor. - pod_vector par_rec_; - - /// Character strings ('\\0' terminated) in the recording. - pod_vector text_rec_; -// ---------------------- Public Functions ----------------------------------- -public: - /// Default constructor - recorder(void) : - thread_offset_( thread_alloc::thread_num() * CPPAD_HASH_TABLE_SIZE ) , - num_var_rec_(0) , - num_load_op_rec_(0) , - op_rec_( std::numeric_limits::max() ) , - vecad_ind_rec_( std::numeric_limits::max() ) , - op_arg_rec_( std::numeric_limits::max() ) , - par_rec_( std::numeric_limits::max() ) , - text_rec_( std::numeric_limits::max() ) - { - abort_op_index_ = 0; - } - - /// Set the abort index - void set_abort_op_index(size_t abort_op_index) - { abort_op_index_ = abort_op_index; } - - /// Get the abort index - size_t get_abort_op_index(void) - { return abort_op_index_; } - - /// Destructor - ~recorder(void) - { } - - /*! - Frees all information in recording. - - Frees the operation sequence store in this recording - (the operation sequence is empty after this operation). - The buffers used to store the current recording are returned - to the system (so as to conserve on memory). - */ - void free(void) - { num_var_rec_ = 0; - num_load_op_rec_ = 0; - op_rec_.free(); - vecad_ind_rec_.free(); - op_arg_rec_.free(); - par_rec_.free(); - text_rec_.free(); - } - /// Put next operator in the operation sequence. - inline size_t PutOp(OpCode op); - /// Put a vecad load operator in the operation sequence (special case) - inline size_t PutLoadOp(OpCode op); - /// Add a value to the end of the current vector of VecAD indices. - inline size_t PutVecInd(size_t vec_ind); - /// Find or add a parameter to the current vector of parameters. - inline size_t PutPar(const Base &par); - /// Put one operation argument index in the recording - inline void PutArg(addr_t arg0); - /// Put two operation argument index in the recording - inline void PutArg(addr_t arg0, addr_t arg1); - /// Put three operation argument index in the recording - inline void PutArg(addr_t arg0, addr_t arg1, addr_t arg2); - /// Put four operation argument index in the recording - inline void PutArg(addr_t arg0, addr_t arg1, addr_t arg2, addr_t arg3); - /// Put five operation argument index in the recording - inline void PutArg(addr_t arg0, addr_t arg1, addr_t arg2, addr_t arg3, - addr_t arg4); - /// Put six operation argument index in the recording - inline void PutArg(addr_t arg0, addr_t arg1, addr_t arg2, addr_t arg3, - addr_t arg4, addr_t arg5); - - // Reserve space for a specified number of arguments - inline size_t ReserveArg(size_t n_arg); - - // Replace an argument value - void ReplaceArg(size_t i_arg, size_t value); - - /// Put a character string in the text for this recording. - inline size_t PutTxt(const char *text); - - /// Number of variables currently stored in the recording. - size_t num_var_rec(void) const - { return num_var_rec_; } - - /// Number of LdpOp and LdvOp operations currently in the recording. - size_t num_load_op_rec(void) const - { return num_load_op_rec_; } - - /// Number of operators currently stored in the recording. - size_t num_op_rec(void) const - { return op_rec_.size(); } - - /// Approximate amount of memory used by the recording - size_t Memory(void) const - { return op_rec_.capacity() * sizeof(CPPAD_OP_CODE_TYPE) - + vecad_ind_rec_.capacity() * sizeof(size_t) - + op_arg_rec_.capacity() * sizeof(addr_t) - + par_rec_.capacity() * sizeof(Base) - + text_rec_.capacity() * sizeof(char); - } -}; - -/*! -Put next operator in the operation sequence. - -This sets the op code for the next operation in this recording. -This call must be followed by putting the corresponding -\verbatim - NumArg(op) -\endverbatim -argument indices in the recording. - -\param op -Is the op code corresponding to the the operation that is being -recorded (which must not be LdpOp or LdvOp). - -\return -The return value is the index of the primary (last) variable -corresponding to the result of this operation. -The number of variables corresponding to the operation is given by -\verbatim - NumRes(op) -\endverbatim -With each call to PutOp or PutLoadOp, -the return index increases by the number of variables corresponding -to the call. -This index starts at zero after the default constructor -and after each call to Erase. -*/ -template -inline size_t recorder::PutOp(OpCode op) -{ size_t i = op_rec_.extend(1); - CPPAD_ASSERT_KNOWN( - (abort_op_index_ == 0) || (abort_op_index_ != i), - "Operator index equals abort_op_index in Independent" - ); - op_rec_[i] = static_cast(op); - CPPAD_ASSERT_UNKNOWN( op_rec_.size() == i + 1 ); - CPPAD_ASSERT_UNKNOWN( (op != LdpOp) & (op != LdvOp) ); - - // first operator should be a BeginOp and NumRes( BeginOp ) > 0 - num_var_rec_ += NumRes(op); - CPPAD_ASSERT_UNKNOWN( num_var_rec_ > 0 ); - - return num_var_rec_ - 1; -} - -/*! -Put next LdpOp or LdvOp operator in operation sequence (special cases). - -This sets the op code for the next operation in this recording. -This call must be followed by putting the corresponding -\verbatim - NumArg(op) -\endverbatim -argument indices in the recording. - -\param op -Is the op code corresponding to the the operation that is being -recorded (which must be LdpOp or LdvOp). - -\return -The return value is the index of the primary (last) variable -corresponding to the result of this operation. -The number of variables corresponding to the operation is given by -\verbatim - NumRes(op) -\endverbatim -which must be one for this operation. -With each call to PutLoadOp or PutOp, -the return index increases by the number of variables corresponding -to this call to the call. -This index starts at zero after the default constructor -and after each call to Erase. - -\par num_load_op_rec() -The return value for num_load_op_rec() -increases by one after each call to this function -(and starts at zero after the default constructor or Erase). -*/ -template -inline size_t recorder::PutLoadOp(OpCode op) -{ size_t i = op_rec_.extend(1); - CPPAD_ASSERT_KNOWN( - (abort_op_index_ == 0) || (abort_op_index_ != i), - "This is the abort operator index specified by " - "Independent(x, abort_op_index)." - ); - op_rec_[i] = static_cast(op); - CPPAD_ASSERT_UNKNOWN( op_rec_.size() == i + 1 ); - CPPAD_ASSERT_UNKNOWN( (op == LdpOp) | (op == LdvOp) ); - - // first operator should be a BeginOp and NumRes( BeginOp ) > 0 - num_var_rec_ += NumRes(op); - CPPAD_ASSERT_UNKNOWN( num_var_rec_ > 0 ); - - // count this vecad load operation - num_load_op_rec_++; - - return num_var_rec_ - 1; -} - -/*! -Add a value to the end of the current vector of VecAD indices. - -For each VecAD vector, this routine is used to store the length -of the vector followed by the parameter index corresponding to each -value in the vector. -This value for the elements of the VecAD vector corresponds to the -beginning of the operation sequence. - -\param vec_ind -is the index to be palced at the end of the vector of VecAD indices. - -\return -is the index in the vector of VecAD indices corresponding to this value. -This index starts at zero after the recorder default constructor -and after each call to Erase. -It increments by one for each call to PutVecInd.. -*/ -template -inline size_t recorder::PutVecInd(size_t vec_ind) -{ size_t i = vecad_ind_rec_.extend(1); - vecad_ind_rec_[i] = vec_ind; - CPPAD_ASSERT_UNKNOWN( vecad_ind_rec_.size() == i + 1 ); - - return i; -} - -/*! -Find or add a parameter to the current vector of parameters. - -\param par -is the parameter to be found or placed in the vector of parameters. - -\return -is the index in the parameter vector corresponding to this parameter value. -This value is not necessarily placed at the end of the vector -(because values that are identically equal may be reused). -*/ -template -size_t recorder::PutPar(const Base &par) -{ static size_t hash_table[CPPAD_HASH_TABLE_SIZE * CPPAD_MAX_NUM_THREADS]; - size_t i; - size_t code; - - CPPAD_ASSERT_UNKNOWN( - thread_offset_ / CPPAD_HASH_TABLE_SIZE - == - thread_alloc::thread_num() - ); - - // get hash code for this value - code = static_cast( hash_code(par) ); - CPPAD_ASSERT_UNKNOWN( code < CPPAD_HASH_TABLE_SIZE ); - - // If we have a match, return the parameter index - i = hash_table[code + thread_offset_]; - if( i < par_rec_.size() && IdenticalEqualPar(par_rec_[i], par) ) - return i; - - // place a new value in the table - i = par_rec_.extend(1); - par_rec_[i] = par; - CPPAD_ASSERT_UNKNOWN( par_rec_.size() == i + 1 ); - - // make the hash code point to this new value - hash_table[code + thread_offset_] = i; - - // return the parameter index - return i; -} -// -------------------------- PutArg -------------------------------------- -/*! -Prototype for putting operation argument indices in the recording. - -The following syntax -\verbatim - rec.PutArg(arg0) - rec.PutArg(arg0, arg1) - . - . - . - rec.PutArg(arg0, arg1, ..., arg5) -\endverbatim -places the values passed to PutArg at the current end of the -operation argument indices for the recording. -\a arg0 comes before \a arg1, etc. -The proper number of operation argument indices -corresponding to the operation code op is given by -\verbatim - NumArg(op) -\endverbatim -The number of the operation argument indices starts at zero -after the default constructor and each call to Erase. -It increases by the number of indices placed by each call to PutArg. -*/ -inline void prototype_put_arg(void) -{ // This routine should not be called - CPPAD_ASSERT_UNKNOWN(false); -} -/*! -Put one operation argument index in the recording - -\param arg0 -The operation argument index - -\copydetails prototype_put_arg -*/ -template -inline void recorder::PutArg(addr_t arg0) -{ - size_t i = op_arg_rec_.extend(1); - op_arg_rec_[i] = static_cast( arg0 ); - CPPAD_ASSERT_UNKNOWN( op_arg_rec_.size() == i + 1 ); -} -/*! -Put two operation argument index in the recording - -\param arg0 -First operation argument index. - -\param arg1 -Second operation argument index. - -\copydetails prototype_put_arg -*/ -template -inline void recorder::PutArg(addr_t arg0, addr_t arg1) -{ - size_t i = op_arg_rec_.extend(2); - op_arg_rec_[i++] = static_cast( arg0 ); - op_arg_rec_[i] = static_cast( arg1 ); - CPPAD_ASSERT_UNKNOWN( op_arg_rec_.size() == i + 1 ); -} -/*! -Put three operation argument index in the recording - -\param arg0 -First operation argument index. - -\param arg1 -Second operation argument index. - -\param arg2 -Third operation argument index. - -\copydetails prototype_put_arg -*/ -template -inline void recorder::PutArg(addr_t arg0, addr_t arg1, addr_t arg2) -{ - size_t i = op_arg_rec_.extend(3); - op_arg_rec_[i++] = static_cast( arg0 ); - op_arg_rec_[i++] = static_cast( arg1 ); - op_arg_rec_[i] = static_cast( arg2 ); - CPPAD_ASSERT_UNKNOWN( op_arg_rec_.size() == i + 1 ); -} -/*! -Put four operation argument index in the recording - -\param arg0 -First operation argument index. - -\param arg1 -Second operation argument index. - -\param arg2 -Third operation argument index. - -\param arg3 -Fourth operation argument index. - -\copydetails prototype_put_arg -*/ -template -inline void recorder::PutArg(addr_t arg0, addr_t arg1, addr_t arg2, - addr_t arg3) -{ - size_t i = op_arg_rec_.extend(4); - op_arg_rec_[i++] = static_cast( arg0 ); - op_arg_rec_[i++] = static_cast( arg1 ); - op_arg_rec_[i++] = static_cast( arg2 ); - op_arg_rec_[i] = static_cast( arg3 ); - CPPAD_ASSERT_UNKNOWN( op_arg_rec_.size() == i + 1 ); - -} -/*! -Put five operation argument index in the recording - -\param arg0 -First operation argument index. - -\param arg1 -Second operation argument index. - -\param arg2 -Third operation argument index. - -\param arg3 -Fourth operation argument index. - -\param arg4 -Fifth operation argument index. - -\copydetails prototype_put_arg -*/ -template -inline void recorder::PutArg(addr_t arg0, addr_t arg1, addr_t arg2, - addr_t arg3, addr_t arg4) -{ - size_t i = op_arg_rec_.extend(5); - op_arg_rec_[i++] = static_cast( arg0 ); - op_arg_rec_[i++] = static_cast( arg1 ); - op_arg_rec_[i++] = static_cast( arg2 ); - op_arg_rec_[i++] = static_cast( arg3 ); - op_arg_rec_[i] = static_cast( arg4 ); - CPPAD_ASSERT_UNKNOWN( op_arg_rec_.size() == i + 1 ); - -} -/*! -Put six operation argument index in the recording - -\param arg0 -First operation argument index. - -\param arg1 -Second operation argument index. - -\param arg2 -Third operation argument index. - -\param arg3 -Fourth operation argument index. - -\param arg4 -Fifth operation argument index. - -\param arg5 -Sixth operation argument index. - -\copydetails prototype_put_arg -*/ -template -inline void recorder::PutArg(addr_t arg0, addr_t arg1, addr_t arg2, - addr_t arg3, addr_t arg4, addr_t arg5) -{ - size_t i = op_arg_rec_.extend(6); - op_arg_rec_[i++] = static_cast( arg0 ); - op_arg_rec_[i++] = static_cast( arg1 ); - op_arg_rec_[i++] = static_cast( arg2 ); - op_arg_rec_[i++] = static_cast( arg3 ); - op_arg_rec_[i++] = static_cast( arg4 ); - op_arg_rec_[i] = static_cast( arg5 ); - CPPAD_ASSERT_UNKNOWN( op_arg_rec_.size() == i + 1 ); -} -// -------------------------------------------------------------------------- -/*! -Reserve space for arguments, but delay placing values there. - -\param n_arg -number of arguements to reserve space for - -\return -is the index in the argument vector corresponding to the -first of the arguments being reserved. -*/ -template -inline size_t recorder::ReserveArg(size_t n_arg) -{ - size_t i = op_arg_rec_.extend(n_arg); - CPPAD_ASSERT_UNKNOWN( op_arg_rec_.size() == i + n_arg ); - return i; -} - -/*! -\brief -Replace an argument value in the recording -(intended to fill in reserved values). - -\param i_arg -is the index, in argument vector, for the value that is replaced. - -\param value -is the new value for the argument with the specified index. -*/ -template -inline void recorder::ReplaceArg(size_t i_arg, size_t value) -{ op_arg_rec_[i_arg] = static_cast( value ); } -// -------------------------------------------------------------------------- -/*! -Put a character string in the text for this recording. - -\param text -is a '\\0' terminated character string that is to be put in the -vector of characters corresponding to this recording. -The terminator '\\0' will be included. - -\return -is the offset with in the text vector for this recording at which -the character string starts. -*/ -template -inline size_t recorder::PutTxt(const char *text) -{ - // determine length of the text including terminating '\0' - size_t n = 0; - while( text[n] != '\0' ) - n++; - CPPAD_ASSERT_UNKNOWN( n <= 1000 ); - n++; - CPPAD_ASSERT_UNKNOWN( text[n-1] == '\0' ); - - // copy text including terminating '\0' - size_t i = text_rec_.extend(n); - size_t j; - for(j = 0; j < n; j++) - text_rec_[i + j] = text[j]; - CPPAD_ASSERT_UNKNOWN( text_rec_.size() == i + n ); - - return i; -} -// ------------------------------------------------------------------------- - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/rev_hes_sweep.hpp b/ct_core/include/ct/external/cppad/local/rev_hes_sweep.hpp deleted file mode 100644 index cbcc61283..000000000 --- a/ct_core/include/ct/external/cppad/local/rev_hes_sweep.hpp +++ /dev/null @@ -1,970 +0,0 @@ -// $Id: rev_hes_sweep.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_REV_HES_SWEEP_HPP -# define CPPAD_REV_HES_SWEEP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file rev_hes_sweep.hpp -Compute Reverse mode Hessian sparsity patterns. -*/ - -/*! -\def CPPAD_REV_HES_SWEEP_TRACE -This value is either zero or one. -Zero is the normal operational value. -If it is one, a trace of every rev_hes_sweep computation is printed. -*/ -# define CPPAD_REV_HES_SWEEP_TRACE 0 - -/*! -Given the forward Jacobian sparsity pattern for all the variables, -and the reverse Jacobian sparsity pattern for the dependent variables, -RevHesSweep computes the Hessian sparsity pattern for all the independent -variables. - -\tparam Base -base type for the operator; i.e., this operation sequence was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param n -is the number of independent variables on the tape. - -\param numvar -is the total number of variables on the tape; i.e., -\a play->num_var_rec(). -This is also the number of rows in the entire sparsity pattern -\a rev_hes_sparse. - -\param play -The information stored in \a play -is a recording of the operations corresponding to a function -\f[ - F : {\bf R}^n \rightarrow {\bf R}^m -\f] -where \f$ n \f$ is the number of independent variables -and \f$ m \f$ is the number of dependent variables. -The object \a play is effectly constant. -It is not declared const because while playing back the tape -the object \a play holds information about the currentl location -with in the tape and this changes during playback. - -\param for_jac_sparse -For i = 0 , ... , \a numvar - 1, -(for all the variables on the tape), -the forward Jacobian sparsity pattern for the variable with index i -corresponds to the set with index i in \a for_jac_sparse. - -\param RevJac -\b Input: -For i = 0, ... , \a numvar - 1 -the if the variable with index i on the tape is an dependent variable and -included in the Hessian, \a RevJac[ i ] is equal to true, -otherwise it is equal to false. -\n -\n -\b Output: The values in \a RevJac upon return are not specified; i.e., -it is used for temporary work space. - -\param rev_hes_sparse -The reverse Hessian sparsity pattern for the variable with index i -corresponds to the set with index i in \a rev_hes_sparse. -\n -\n -\b Input: For i = 0 , ... , \a numvar - 1 -the reverse Hessian sparsity pattern for the variable with index i is empty. -\n -\n -\b Output: For j = 1 , ... , \a n, -the reverse Hessian sparsity pattern for the independent dependent variable -with index (j-1) is given by the set with index j -in \a rev_hes_sparse. -The values in the rest of \a rev_hes_sparse are not specified; i.e., -they are used for temporary work space. -*/ - -template -void RevHesSweep( - size_t n, - size_t numvar, - player *play, - Vector_set& for_jac_sparse, // should be const - bool* RevJac, - Vector_set& rev_hes_sparse -) -{ - OpCode op; - size_t i_op; - size_t i_var; - - const addr_t* arg = CPPAD_NULL; - - // length of the parameter vector (used by CppAD assert macros) - const size_t num_par = play->num_par_rec(); - - size_t i, j, k; - - // check numvar argument - CPPAD_ASSERT_UNKNOWN( play->num_var_rec() == numvar ); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse.n_set() == numvar ); - CPPAD_ASSERT_UNKNOWN( rev_hes_sparse.n_set() == numvar ); - CPPAD_ASSERT_UNKNOWN( numvar > 0 ); - - // upper limit exclusive for set elements - size_t limit = rev_hes_sparse.end(); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse.end() == limit ); - - // check number of sets match - CPPAD_ASSERT_UNKNOWN( - for_jac_sparse.n_set() == rev_hes_sparse.n_set() - ); - - // vecad_sparsity contains a sparsity pattern for each VecAD object. - // vecad_ind maps a VecAD index (beginning of the VecAD object) - // to the index for the corresponding set in vecad_sparsity. - size_t num_vecad_ind = play->num_vec_ind_rec(); - size_t num_vecad_vec = play->num_vecad_vec_rec(); - Vector_set vecad_sparse; - vecad_sparse.resize(num_vecad_vec, limit); - pod_vector vecad_ind; - pod_vector vecad_jac; - if( num_vecad_vec > 0 ) - { size_t length; - vecad_ind.extend(num_vecad_ind); - vecad_jac.extend(num_vecad_vec); - j = 0; - for(i = 0; i < num_vecad_vec; i++) - { // length of this VecAD - length = play->GetVecInd(j); - // set vecad_ind to proper index for this VecAD - vecad_ind[j] = i; - // make all other values for this vector invalid - for(k = 1; k <= length; k++) - vecad_ind[j+k] = num_vecad_vec; - // start of next VecAD - j += length + 1; - // initialize this vector's reverse jacobian value - vecad_jac[i] = false; - } - CPPAD_ASSERT_UNKNOWN( j == play->num_vec_ind_rec() ); - } - - // work space used by UserOp. - vector user_ix; // variable indices for argument vector x - typedef std::set size_set; - size_set::iterator set_itr; // iterator for a standard set - size_set::iterator set_end; // end of iterator sequence - vector< size_set > set_r; // forward Jacobian sparsity for x - vector< size_set > set_u; // reverse Hessian sparsity for y - vector< size_set > set_v; // reverse Hessian sparsity for x - // - vector bool_r; // bool forward Jacobian sparsity for x - vector bool_u; // bool reverse Hessian sparsity for y - vector bool_v; // bool reverse Hessian sparsity for x - // - vectorBool pack_r; // pack forward Jacobian sparsity for x - vectorBool pack_u; // pack reverse Hessian sparsity for y - vectorBool pack_v; // pack reverse Hessian sparsity for x - // - vector user_vx; // which components of x are variables - vector user_s; // reverse Jacobian sparsity for y - vector user_t; // reverse Jacobian sparsity for x - const size_t user_q = limit; // maximum element plus one - size_t user_index = 0; // indentifier for this atomic operation - size_t user_id = 0; // user identifier for this call to operator - size_t user_i = 0; // index in result vector - size_t user_j = 0; // index in argument vector - size_t user_m = 0; // size of result vector - size_t user_n = 0; // size of arugment vector - // - atomic_base* user_atom = CPPAD_NULL; // user's atomic op calculator - bool user_pack = false; // sparsity pattern type is pack - bool user_bool = false; // sparsity pattern type is bool - bool user_set = false; // sparsity pattern type is set -# ifndef NDEBUG - bool user_ok = false; // atomic op return value -# endif - // next expected operator in a UserOp sequence - enum { user_start, user_arg, user_ret, user_end } user_state = user_end; - - - // Initialize - play->reverse_start(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( op == EndOp ); -# if CPPAD_REV_HES_SWEEP_TRACE - std::cout << std::endl; - CppAD::vectorBool zf_value(limit); - CppAD::vectorBool zh_value(limit); -# endif - bool more_operators = true; - while(more_operators) - { - // next op - play->reverse_next(op, arg, i_op, i_var); -# ifndef NDEBUG - if( i_op <= n ) - { CPPAD_ASSERT_UNKNOWN((op == InvOp) | (op == BeginOp)); - } - else CPPAD_ASSERT_UNKNOWN((op != InvOp) & (op != BeginOp)); -# endif - - // rest of information depends on the case - switch( op ) - { - case AbsOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1) - reverse_sparse_hessian_linear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case AddvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - reverse_sparse_hessian_addsub_op( - i_var, arg, RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case AddpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - reverse_sparse_hessian_linear_unary_op( - i_var, arg[1], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case AcosOp: - // sqrt(1 - x * x), acos(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AcoshOp: - // sqrt(x * x - 1), acosh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; -# endif - // ------------------------------------------------- - - case AsinOp: - // sqrt(1 - x * x), asin(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AsinhOp: - // sqrt(1 + x * x), asinh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; -# endif - // ------------------------------------------------- - - case AtanOp: - // 1 + x * x, atan(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AtanhOp: - // 1 - x * x, atanh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; -# endif - // ------------------------------------------------- - - case BeginOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1) - more_operators = false; - break; - // ------------------------------------------------- - - case CSkipOp: - // CSkipOp has a variable number of arguments and - // reverse_next thinks it one has one argument. - // We must inform reverse_next of this special case. - play->reverse_cskip(op, arg, i_op, i_var); - break; - // ------------------------------------------------- - - case CSumOp: - // CSumOp has a variable number of arguments and - // reverse_next thinks it one has one argument. - // We must inform reverse_next of this special case. - play->reverse_csum(op, arg, i_op, i_var); - reverse_sparse_hessian_csum_op( - i_var, arg, RevJac, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case CExpOp: - reverse_sparse_hessian_cond_op( - i_var, arg, num_par, RevJac, rev_hes_sparse - ); - break; - // --------------------------------------------------- - - case CosOp: - // sin(x), cos(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // --------------------------------------------------- - - case CoshOp: - // sinh(x), cosh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case DisOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - // derivativve is identically zero - break; - // ------------------------------------------------- - - case DivvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - reverse_sparse_hessian_div_op( - i_var, arg, RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case DivpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[1], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case DivvpOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - reverse_sparse_hessian_linear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case ErfOp: - // arg[1] is always the parameter 0 - // arg[0] is always the parameter 2 / sqrt(pi) - CPPAD_ASSERT_NARG_NRES(op, 3, 5); - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case ExpOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case Expm1Op: - CPPAD_ASSERT_NARG_NRES(op, 1, 1) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; -# endif - // ------------------------------------------------- - - case InvOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 1) - // Z is already defined - break; - // ------------------------------------------------- - - case LdpOp: - reverse_sparse_hessian_load_op( - op, - i_var, - arg, - num_vecad_ind, - vecad_ind.data(), - rev_hes_sparse, - vecad_sparse, - RevJac, - vecad_jac.data() - ); - break; - // ------------------------------------------------- - - case LdvOp: - reverse_sparse_hessian_load_op( - op, - i_var, - arg, - num_vecad_ind, - vecad_ind.data(), - rev_hes_sparse, - vecad_sparse, - RevJac, - vecad_jac.data() - ); - break; - // ------------------------------------------------- - - case EqpvOp: - case EqvvOp: - case LtpvOp: - case LtvpOp: - case LtvvOp: - case LepvOp: - case LevpOp: - case LevvOp: - case NepvOp: - case NevvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 0); - break; - // ------------------------------------------------- - - case LogOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case Log1pOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; -# endif - // ------------------------------------------------- - - case MulpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - reverse_sparse_hessian_linear_unary_op( - i_var, arg[1], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case MulvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - reverse_sparse_hessian_mul_op( - i_var, arg, RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case ParOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1) - - break; - // ------------------------------------------------- - - case PowpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 3) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[1], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case PowvpOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 3) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case PowvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 3) - reverse_sparse_hessian_pow_op( - i_var, arg, RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case PriOp: - CPPAD_ASSERT_NARG_NRES(op, 5, 0); - break; - // ------------------------------------------------- - - case SignOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - // Derivative is identiaclly zero - break; - // ------------------------------------------------- - - case SinOp: - // cos(x), sin(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case SinhOp: - // cosh(x), sinh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case SqrtOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case StppOp: - // sparsity cannot propagate through a parameter - CPPAD_ASSERT_NARG_NRES(op, 3, 0) - break; - // ------------------------------------------------- - - case StpvOp: - reverse_sparse_hessian_store_op( - op, - arg, - num_vecad_ind, - vecad_ind.data(), - rev_hes_sparse, - vecad_sparse, - RevJac, - vecad_jac.data() - ); - break; - // ------------------------------------------------- - - case StvpOp: - // sparsity cannot propagate through a parameter - CPPAD_ASSERT_NARG_NRES(op, 3, 0) - break; - // ------------------------------------------------- - - case StvvOp: - reverse_sparse_hessian_store_op( - op, - arg, - num_vecad_ind, - vecad_ind.data(), - rev_hes_sparse, - vecad_sparse, - RevJac, - vecad_jac.data() - ); - break; - // ------------------------------------------------- - - case SubvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - reverse_sparse_hessian_addsub_op( - i_var, arg, RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case SubpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - reverse_sparse_hessian_linear_unary_op( - i_var, arg[1], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case SubvpOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - reverse_sparse_hessian_linear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case TanOp: - // tan(x)^2, tan(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case TanhOp: - // tanh(x)^2, tanh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2) - reverse_sparse_hessian_nonlinear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case UserOp: - // start or end an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( NumRes( UserOp ) == 0 ); - CPPAD_ASSERT_UNKNOWN( NumArg( UserOp ) == 4 ); - if( user_state == user_end ) - { user_index = arg[0]; - user_id = arg[1]; - user_n = arg[2]; - user_m = arg[3]; - user_atom = atomic_base::class_object(user_index); -# ifndef NDEBUG - if( user_atom == CPPAD_NULL ) - { std::string msg = - atomic_base::class_name(user_index) - + ": atomic_base function has been deleted"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - user_pack = user_atom->sparsity() == - atomic_base::pack_sparsity_enum; - user_bool = user_atom->sparsity() == - atomic_base::bool_sparsity_enum; - user_set = user_atom->sparsity() == - atomic_base::set_sparsity_enum; - CPPAD_ASSERT_UNKNOWN( user_pack || user_bool || user_set ); - user_ix.resize(user_n); - user_vx.resize(user_n); - user_s.resize(user_m); - user_t.resize(user_n); - - // simpler to initialize all sparsity patterns as empty - for(i = 0; i < user_m; i++) - user_s[i] = false; - for(i = 0; i < user_n; i++) - user_t[i] = false; - if( user_pack ) - { pack_r.resize(user_n * user_q); - pack_u.resize(user_m * user_q); - pack_v.resize(user_n * user_q); - // simpler to initialize all patterns as empty - for(i = 0; i < user_m; i++) - { - for(j = 0; j < user_q; j++) - pack_u[ i * user_q + j] = false; - } - for(i = 0; i < user_n; i++) - { - for(j = 0; j < user_q; j++) - { pack_r[ i * user_q + j] = false; - pack_v[ i * user_q + j] = false; - } - } - } - if( user_bool ) - { bool_r.resize(user_n * user_q); - bool_u.resize(user_m * user_q); - bool_v.resize(user_n * user_q); - // simpler to initialize all patterns as empty - for(i = 0; i < user_m; i++) - { - for(j = 0; j < user_q; j++) - bool_u[ i * user_q + j] = false; - } - for(i = 0; i < user_n; i++) - { - for(j = 0; j < user_q; j++) - { bool_r[ i * user_q + j] = false; - bool_v[ i * user_q + j] = false; - } - } - } - if( user_set ) - { set_r.resize(user_n); - set_u.resize(user_m); - set_v.resize(user_n); - for(i = 0; i < user_m; i++) - set_u[i].clear(); - for(i = 0; i < user_n; i++) - { set_r[i].clear(); - set_v[i].clear(); - } - } - user_j = user_n; - user_i = user_m; - user_state = user_ret; - } - else - { CPPAD_ASSERT_UNKNOWN( user_state == user_start ); - CPPAD_ASSERT_UNKNOWN( user_index == size_t(arg[0]) ); - CPPAD_ASSERT_UNKNOWN( user_id == size_t(arg[1]) ); - CPPAD_ASSERT_UNKNOWN( user_n == size_t(arg[2]) ); - CPPAD_ASSERT_UNKNOWN( user_m == size_t(arg[3]) ); - user_state = user_end; - - // call users function for this operation - user_atom->set_id(user_id); -# ifdef NDEBUG - if( user_pack ) - user_atom->rev_sparse_hes(user_vx, - user_s, user_t, user_q, pack_r, pack_u, pack_v - ); - if( user_bool ) - user_atom->rev_sparse_hes(user_vx, - user_s, user_t, user_q, bool_r, bool_u, bool_v - ); - if( user_set ) - user_atom->rev_sparse_hes(user_vx, - user_s, user_t, user_q, set_r, set_u, set_v - ); -# else - if( user_pack ) - user_ok = user_atom->rev_sparse_hes(user_vx, - user_s, user_t, user_q, pack_r, pack_u, pack_v - ); - if( user_bool ) - user_ok = user_atom->rev_sparse_hes(user_vx, - user_s, user_t, user_q, bool_r, bool_u, bool_v - ); - if( user_set ) - user_ok = user_atom->rev_sparse_hes(user_vx, - user_s, user_t, user_q, set_r, set_u, set_v - ); - if( ! user_ok ) - { std::string msg = - atomic_base::class_name(user_index) - + ": atomic_base.rev_sparse_hes: returned false\n"; - if( user_pack ) - msg += "sparsity = pack_sparsity_enum"; - if( user_bool ) - msg += "sparsity = bool_sparsity_enum"; - if( user_set ) - msg += "sparsity = set_sparsity_enum"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - for(i = 0; i < user_n; i++) if( user_ix[i] > 0 ) - { - size_t i_x = user_ix[i]; - if( user_t[i] ) - RevJac[i_x] = true; - if( user_pack ) - { - for(j = 0; j < user_q; j++) - if( pack_v[ i * user_q + j ] ) - rev_hes_sparse.add_element(i_x, j); - } - if( user_bool ) - { - for(j = 0; j < user_q; j++) - if( bool_v[ i * user_q + j ] ) - rev_hes_sparse.add_element(i_x, j); - } - if( user_set ) - { - set_itr = set_v[i].begin(); - set_end = set_v[i].end(); - while( set_itr != set_end ) - rev_hes_sparse.add_element(i_x, *set_itr++); - } - } - } - break; - - case UsrapOp: - // parameter argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( 0 < user_j && user_j <= user_n ); - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - --user_j; - user_ix[user_j] = 0; - user_vx[user_j] = false; - if( user_j == 0 ) - user_state = user_start; - break; - - case UsravOp: - // variable argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( 0 < user_j && user_j <= user_n ); - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) <= i_var ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - --user_j; - user_ix[user_j] = arg[0]; - user_vx[user_j] = true; - for_jac_sparse.begin(arg[0]); - i = for_jac_sparse.next_element(); - while( i < user_q ) - { if( user_pack ) - pack_r[ user_j * user_q + i ] = true; - if( user_bool ) - bool_r[ user_j * user_q + i ] = true; - if( user_set ) - set_r[user_j].insert(i); - i = for_jac_sparse.next_element(); - } - if( user_j == 0 ) - user_state = user_start; - break; - - case UsrrpOp: - // parameter result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( 0 < user_i && user_i <= user_m ); - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - --user_i; - if( user_i == 0 ) - user_state = user_arg; - break; - - case UsrrvOp: - // variable result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( 0 < user_i && user_i <= user_m ); - --user_i; - if( RevJac[i_var] ) - { - user_s[user_i] = true; - } - rev_hes_sparse.begin(i_var); - j = rev_hes_sparse.next_element(); - while( j < user_q ) - { if( user_pack ) - pack_u[user_i * user_q + j] = true; - if( user_bool ) - bool_u[user_i * user_q + j] = true; - if( user_set ) - set_u[user_i].insert(j); - j = rev_hes_sparse.next_element(); - } - if( user_i == 0 ) - user_state = user_arg; - break; - // ------------------------------------------------- - - case ZmulpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - reverse_sparse_hessian_linear_unary_op( - i_var, arg[1], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case ZmulvpOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - reverse_sparse_hessian_linear_unary_op( - i_var, arg[0], RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - // ------------------------------------------------- - - case ZmulvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1) - reverse_sparse_hessian_mul_op( - i_var, arg, RevJac, for_jac_sparse, rev_hes_sparse - ); - break; - - // ------------------------------------------------- - - default: - CPPAD_ASSERT_UNKNOWN(0); - } -# if CPPAD_REV_HES_SWEEP_TRACE - for(j = 0; j < limit; j++) - { zf_value[j] = false; - zh_value[j] = false; - } - for_jac_sparse.begin(i_var);; - j = for_jac_sparse.next_element();; - while( j < limit ) - { zf_value[j] = true; - j = for_jac_sparse.next_element(); - } - rev_hes_sparse.begin(i_var);; - j = rev_hes_sparse.next_element();; - while( j < limit ) - { zh_value[j] = true; - j = rev_hes_sparse.next_element(); - } - printOp( - std::cout, - play, - i_op, - i_var, - op, - arg - ); - // should also print RevJac[i_var], but printOpResult does not - // yet allow for this - if( NumRes(op) > 0 && op != BeginOp ) printOpResult( - std::cout, - 1, - &zf_value, - 1, - &zh_value - ); - std::cout << std::endl; - } - std::cout << std::endl; -# else - } -# endif - // values corresponding to BeginOp - CPPAD_ASSERT_UNKNOWN( i_op == 0 ); - CPPAD_ASSERT_UNKNOWN( i_var == 0 ); - - return; -} -} // END_CPPAD_NAMESPACE - -// preprocessor symbols that are local to this file -# undef CPPAD_REV_HES_SWEEP_TRACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/rev_jac_sweep.hpp b/ct_core/include/ct/external/cppad/local/rev_jac_sweep.hpp deleted file mode 100644 index 9caa9f7e6..000000000 --- a/ct_core/include/ct/external/cppad/local/rev_jac_sweep.hpp +++ /dev/null @@ -1,890 +0,0 @@ -// $Id: rev_jac_sweep.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_REV_JAC_SWEEP_HPP -# define CPPAD_REV_JAC_SWEEP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file rev_jac_sweep.hpp -Compute Reverse mode Jacobian sparsity patterns. -*/ - -/*! -\def CPPAD_REV_JAC_SWEEP_TRACE -This value is either zero or one. -Zero is the normal operational value. -If it is one, a trace of every rev_jac_sweep computation is printed. -*/ -# define CPPAD_REV_JAC_SWEEP_TRACE 0 - -/* -\def CPPAD_ATOMIC_CALL -This avoids warnings when NDEBUG is defined and user_ok is not used. -If \c NDEBUG is defined, this resolves to -\code - user_atom->rev_sparse_jac -\endcode -otherwise, it respolves to -\code - user_ok = user_atom->rev_sparse_jac -\endcode -This maco is undefined at the end of this file to facillitate is -use with a different definition in other files. -*/ -# ifdef NDEBUG -# define CPPAD_ATOMIC_CALL user_atom->rev_sparse_jac -# else -# define CPPAD_ATOMIC_CALL user_ok = user_atom->rev_sparse_jac -# endif - -/*! -Given the sparsity pattern for the dependent variables, -RevJacSweep computes the sparsity pattern for all the independent variables. - -\tparam Base -base type for the operator; i.e., this operation sequence was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param dependency -Are the derivatives with respect to left and right of the expression below -considered to be non-zero: -\code - CondExpRel(left, right, if_true, if_false) -\endcode -This is used by the optimizer to obtain the correct dependency relations. - -\param n -is the number of independent variables on the tape. - -\param numvar -is the total number of variables on the tape; i.e., -\a play->num_var_rec(). -This is also the number of rows in the entire sparsity pattern \a RevJac. - -\param play -The information stored in \a play -is a recording of the operations corresponding to a function -\f[ - F : {\bf R}^n \rightarrow {\bf R}^m -\f] -where \f$ n \f$ is the number of independent variables -and \f$ m \f$ is the number of dependent variables. -The object \a play is effectly constant. -It is not declared const because while playing back the tape -the object \a play holds information about the currentl location -with in the tape and this changes during playback. - -\param var_sparsity -For i = 0 , ... , \a numvar - 1, -(all the variables on the tape) -the forward Jacobian sparsity pattern for variable i -corresponds to the set with index i in \a var_sparsity. -\b -\b -\b Input: -For i = 0 , ... , \a numvar - 1, -the forward Jacobian sparsity pattern for variable i is an input -if i corresponds to a dependent variable. -Otherwise the sparsity patten is empty. -\n -\n -\b Output: For j = 1 , ... , \a n, -the sparsity pattern for the dependent variable with index (j-1) -is given by the set with index index j in \a var_sparsity. -*/ - -template -void RevJacSweep( - bool dependency, - size_t n, - size_t numvar, - player *play, - Vector_set& var_sparsity -) -{ - OpCode op; - size_t i_op; - size_t i_var; - - const addr_t* arg = CPPAD_NULL; - - size_t i, j, k; - - // length of the parameter vector (used by CppAD assert macros) - const size_t num_par = play->num_par_rec(); - - // check numvar argument - CPPAD_ASSERT_UNKNOWN( numvar > 0 ); - CPPAD_ASSERT_UNKNOWN( play->num_var_rec() == numvar ); - CPPAD_ASSERT_UNKNOWN( var_sparsity.n_set() == numvar ); - - // upper limit (exclusive) for elements in the set - size_t limit = var_sparsity.end(); - - // vecad_sparsity contains a sparsity pattern for each VecAD object. - // vecad_ind maps a VecAD index (beginning of the VecAD object) - // to the index of the corresponding set in vecad_sparsity. - size_t num_vecad_ind = play->num_vec_ind_rec(); - size_t num_vecad_vec = play->num_vecad_vec_rec(); - Vector_set vecad_sparsity; - vecad_sparsity.resize(num_vecad_vec, limit); - pod_vector vecad_ind; - if( num_vecad_vec > 0 ) - { size_t length; - vecad_ind.extend(num_vecad_ind); - j = 0; - for(i = 0; i < num_vecad_vec; i++) - { // length of this VecAD - length = play->GetVecInd(j); - // set to proper index for this VecAD - vecad_ind[j] = i; - for(k = 1; k <= length; k++) - vecad_ind[j+k] = num_vecad_vec; // invalid index - // start of next VecAD - j += length + 1; - } - CPPAD_ASSERT_UNKNOWN( j == play->num_vec_ind_rec() ); - } - - // work space used by UserOp. - typedef std::set size_set; - size_set::iterator set_itr; // iterator for a standard set - size_set::iterator set_end; // end of iterator sequence - vector< size_set > set_r; // set sparsity pattern for the argument x - vector< size_set > set_s; // set sparisty pattern for the result y - // - vector bool_r; // bool sparsity pattern for the argument x - vector bool_s; // bool sparisty pattern for the result y - // - vectorBool pack_r; // pack sparsity pattern for the argument x - vectorBool pack_s; // pack sparisty pattern for the result y - // - const size_t user_q = limit; // maximum element plus one - size_t user_index = 0; // indentifier for this atomic operation - size_t user_id = 0; // user identifier for this call to operator - size_t user_i = 0; // index in result vector - size_t user_j = 0; // index in argument vector - size_t user_m = 0; // size of result vector - size_t user_n = 0; // size of arugment vector - // - atomic_base* user_atom = CPPAD_NULL; // user's atomic op calculator - bool user_pack = false; // sparsity pattern type is pack - bool user_bool = false; // sparsity pattern type is bool - bool user_set = false; // sparsity pattern type is set -# ifndef NDEBUG - bool user_ok = false; // atomic op return value -# endif - // next expected operator in a UserOp sequence - enum { user_start, user_arg, user_ret, user_end } user_state = user_end; - - // Initialize - play->reverse_start(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( op == EndOp ); -# if CPPAD_REV_JAC_SWEEP_TRACE - std::cout << std::endl; - CppAD::vectorBool z_value(limit); -# endif - bool more_operators = true; - while(more_operators) - { - // next op - play->reverse_next(op, arg, i_op, i_var); -# ifndef NDEBUG - if( i_op <= n ) - { CPPAD_ASSERT_UNKNOWN((op == InvOp) | (op == BeginOp)); - } - else CPPAD_ASSERT_UNKNOWN((op != InvOp) & (op != BeginOp)); -# endif - - // rest of information depends on the case - switch( op ) - { - case AbsOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case AddvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - reverse_sparse_jacobian_binary_op( - i_var, arg, var_sparsity - ); - break; - // ------------------------------------------------- - - case AddpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - reverse_sparse_jacobian_unary_op( - i_var, arg[1], var_sparsity - ); - break; - // ------------------------------------------------- - - case AcosOp: - // sqrt(1 - x * x), acos(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AcoshOp: - // sqrt(x * x - 1), acosh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; -# endif - // ------------------------------------------------- - - case AsinOp: - // sqrt(1 - x * x), asin(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AsinhOp: - // sqrt(1 + x * x), asinh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; -# endif - // ------------------------------------------------- - - case AtanOp: - // 1 + x * x, atan(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AtanhOp: - // 1 - x * x, atanh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; -# endif - // ------------------------------------------------- - - case BeginOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - more_operators = false; - break; - // ------------------------------------------------- - - case CSkipOp: - // CSkipOp has a variable number of arguments and - // reverse_next thinks it one has one argument. - // We must inform reverse_next of this special case. - play->reverse_cskip(op, arg, i_op, i_var); - break; - // ------------------------------------------------- - - case CSumOp: - // CSumOp has a variable number of arguments and - // reverse_next thinks it one has one argument. - // We must inform reverse_next of this special case. - play->reverse_csum(op, arg, i_op, i_var); - reverse_sparse_jacobian_csum_op( - i_var, arg, var_sparsity - ); - break; - // ------------------------------------------------- - - case CExpOp: - reverse_sparse_jacobian_cond_op( - dependency, i_var, arg, num_par, var_sparsity - ); - break; - // --------------------------------------------------- - - case CosOp: - // sin(x), cos(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // --------------------------------------------------- - - case CoshOp: - // sinh(x), cosh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case DisOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - // derivative is identically zero but dependency is not - if( dependency ) reverse_sparse_jacobian_unary_op( - i_var, arg[1], var_sparsity - ); - break; - // ------------------------------------------------- - - case DivvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - reverse_sparse_jacobian_binary_op( - i_var, arg, var_sparsity - ); - break; - // ------------------------------------------------- - - case DivpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - reverse_sparse_jacobian_unary_op( - i_var, arg[1], var_sparsity - ); - break; - // ------------------------------------------------- - - case DivvpOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case ErfOp: - // arg[1] is always the parameter 0 - // arg[0] is always the parameter 2 / sqrt(pi) - CPPAD_ASSERT_NARG_NRES(op, 3, 5); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case ExpOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case Expm1Op: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; -# endif - // ------------------------------------------------- - - case InvOp: - CPPAD_ASSERT_NARG_NRES(op, 0, 1); - break; - // ------------------------------------------------- - - case LdpOp: - reverse_sparse_jacobian_load_op( - dependency, - op, - i_var, - arg, - num_vecad_ind, - vecad_ind.data(), - var_sparsity, - vecad_sparsity - ); - break; - // ------------------------------------------------- - - case LdvOp: - reverse_sparse_jacobian_load_op( - dependency, - op, - i_var, - arg, - num_vecad_ind, - vecad_ind.data(), - var_sparsity, - vecad_sparsity - ); - break; - // ------------------------------------------------- - - case EqpvOp: - case EqvvOp: - case LtpvOp: - case LtvpOp: - case LtvvOp: - case LepvOp: - case LevpOp: - case LevvOp: - case NepvOp: - case NevvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 0); - break; - // ------------------------------------------------- - - case LogOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case Log1pOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; -# endif - // ------------------------------------------------- - - case MulpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - reverse_sparse_jacobian_unary_op( - i_var, arg[1], var_sparsity - ); - break; - // ------------------------------------------------- - - case MulvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - reverse_sparse_jacobian_binary_op( - i_var, arg, var_sparsity - ); - break; - // ------------------------------------------------- - - case ParOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - - break; - // ------------------------------------------------- - - case PowvpOp: - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case PowpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 3); - reverse_sparse_jacobian_unary_op( - i_var, arg[1], var_sparsity - ); - break; - // ------------------------------------------------- - - case PowvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 3); - reverse_sparse_jacobian_binary_op( - i_var, arg, var_sparsity - ); - break; - // ------------------------------------------------- - - case PriOp: - CPPAD_ASSERT_NARG_NRES(op, 5, 0); - break; - // ------------------------------------------------- - - case SignOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - // derivative is identically zero but dependency is not - if( dependency ) reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case SinOp: - // cos(x), sin(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case SinhOp: - // cosh(x), sinh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case SqrtOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case StppOp: - // does not affect sparsity or dependency when both are parameters - CPPAD_ASSERT_NARG_NRES(op, 3, 0); - break; - // ------------------------------------------------- - - case StpvOp: - reverse_sparse_jacobian_store_op( - dependency, - op, - arg, - num_vecad_ind, - vecad_ind.data(), - var_sparsity, - vecad_sparsity - ); - break; - // ------------------------------------------------- - - case StvpOp: - CPPAD_ASSERT_NARG_NRES(op, 3, 0); - // storing a parameter only affects dependency - reverse_sparse_jacobian_store_op( - dependency, - op, - arg, - num_vecad_ind, - vecad_ind.data(), - var_sparsity, - vecad_sparsity - ); - break; - // ------------------------------------------------- - - case StvvOp: - reverse_sparse_jacobian_store_op( - dependency, - op, - arg, - num_vecad_ind, - vecad_ind.data(), - var_sparsity, - vecad_sparsity - ); - break; - // ------------------------------------------------- - - case SubvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - reverse_sparse_jacobian_binary_op( - i_var, arg, var_sparsity - ); - break; - // ------------------------------------------------- - - case SubpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - reverse_sparse_jacobian_unary_op( - i_var, arg[1], var_sparsity - ); - break; - // ------------------------------------------------- - - case SubvpOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case TanOp: - // tan(x)^2, tan(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case TanhOp: - // tanh(x)^2, tanh(x) - CPPAD_ASSERT_NARG_NRES(op, 1, 2); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case UserOp: - // start or end atomic operation sequence - CPPAD_ASSERT_UNKNOWN( NumRes( UserOp ) == 0 ); - CPPAD_ASSERT_UNKNOWN( NumArg( UserOp ) == 4 ); - if( user_state == user_end ) - { user_index = arg[0]; - user_id = arg[1]; - user_n = arg[2]; - user_m = arg[3]; - user_atom = atomic_base::class_object(user_index); -# ifndef NDEBUG - if( user_atom == CPPAD_NULL ) - { std::string msg = - atomic_base::class_name(user_index) - + ": atomic_base function has been deleted"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - user_pack = user_atom->sparsity() == - atomic_base::pack_sparsity_enum; - user_bool = user_atom->sparsity() == - atomic_base::bool_sparsity_enum; - user_set = user_atom->sparsity() == - atomic_base::set_sparsity_enum; - CPPAD_ASSERT_UNKNOWN( user_pack || user_bool || user_set ); - if( user_pack ) - { if( pack_r.size() != user_m * user_q ) - pack_r.resize( user_m * user_q ); - if( pack_s.size() != user_n * user_q ) - pack_s.resize( user_n * user_q ); - for(i = 0; i < user_m; i++) - for(j = 0; j < user_q; j++) - pack_r[ i * user_q + j] = false; - } - if( user_bool ) - { if( bool_r.size() != user_m * user_q ) - bool_r.resize( user_m * user_q ); - if( bool_s.size() != user_n * user_q ) - bool_s.resize( user_n * user_q ); - for(i = 0; i < user_m; i++) - for(j = 0; j < user_q; j++) - bool_r[ i * user_q + j] = false; - } - if( user_set ) - { if(set_r.size() != user_m ) - set_r.resize(user_m); - if(set_s.size() != user_n ) - set_s.resize(user_n); - for(i = 0; i < user_m; i++) - set_r[i].clear(); - } - user_j = user_n; - user_i = user_m; - user_state = user_ret; - } - else - { CPPAD_ASSERT_UNKNOWN( user_state == user_start ); - CPPAD_ASSERT_UNKNOWN( user_index == size_t(arg[0]) ); - CPPAD_ASSERT_UNKNOWN( user_id == size_t(arg[1]) ); - CPPAD_ASSERT_UNKNOWN( user_n == size_t(arg[2]) ); - CPPAD_ASSERT_UNKNOWN( user_m == size_t(arg[3]) ); -# ifndef NDEBUG - if( ! user_ok ) - { std::string msg = - atomic_base::class_name(user_index) - + ": atomic_base.rev_sparse_jac: returned false\n"; - if( user_pack ) - msg += "sparsity = pack_sparsity_enum"; - if( user_bool ) - msg += "sparsity = bool_sparsity_enum"; - if( user_set ) - msg += "sparsity = set_sparsity_enum"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - user_state = user_end; - } - break; - - case UsrapOp: - // parameter argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( 0 < user_j && user_j <= user_n ); - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - --user_j; - if( user_j == 0 ) - user_state = user_start; - break; - - case UsravOp: - // variable argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( 0 < user_j && user_j <= user_n ); - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) <= i_var ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - --user_j; - // 2DO: It might be faster if we add set union to var_sparsity - // where one of the sets is not in var_sparsity. - if( user_pack ) - { for(j = 0; j < user_q; j++) - if( pack_s[ user_j * user_q + j ] ) - var_sparsity.add_element(arg[0], j); - } - if( user_bool ) - { for(j = 0; j < user_q; j++) - if( bool_s[ user_j * user_q + j ] ) - var_sparsity.add_element(arg[0], j); - } - if( user_set ) - { set_itr = set_s[user_j].begin(); - set_end = set_s[user_j].end(); - while( set_itr != set_end ) - var_sparsity.add_element(arg[0], *set_itr++); - } - if( user_j == 0 ) - user_state = user_start; - break; - - case UsrrpOp: - // parameter result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( 0 < user_i && user_i <= user_m ); - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - --user_i; - if( user_i == 0 ) - { // call users function for this operation - user_atom->set_id(user_id); - if( user_pack ) - CPPAD_ATOMIC_CALL( user_q, pack_r, pack_s); - if( user_bool ) - CPPAD_ATOMIC_CALL( user_q, bool_r, bool_s); - if( user_set ) - CPPAD_ATOMIC_CALL( user_q, set_r, set_s); - user_state = user_arg; - } - break; - - case UsrrvOp: - // variable result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( 0 < user_i && user_i <= user_m ); - --user_i; - var_sparsity.begin(i_var); - i = var_sparsity.next_element(); - while( i < user_q ) - { if( user_pack ) - pack_r[ user_i * user_q + i ] = true; - if( user_bool ) - bool_r[ user_i * user_q + i ] = true; - if( user_set ) - set_r[user_i].insert(i); - i = var_sparsity.next_element(); - } - if( user_i == 0 ) - { // call users function for this operation - user_atom->set_id(user_id); - if( user_pack ) - CPPAD_ATOMIC_CALL( user_q, pack_r, pack_s); - if( user_bool ) - CPPAD_ATOMIC_CALL( user_q, bool_r, bool_s); - if( user_set ) - CPPAD_ATOMIC_CALL( user_q, set_r, set_s); - user_state = user_arg; - } - break; - // ------------------------------------------------- - - case ZmulpvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - reverse_sparse_jacobian_unary_op( - i_var, arg[1], var_sparsity - ); - break; - // ------------------------------------------------- - - case ZmulvpOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - reverse_sparse_jacobian_unary_op( - i_var, arg[0], var_sparsity - ); - break; - // ------------------------------------------------- - - case ZmulvvOp: - CPPAD_ASSERT_NARG_NRES(op, 2, 1); - reverse_sparse_jacobian_binary_op( - i_var, arg, var_sparsity - ); - break; - // ------------------------------------------------- - - default: - CPPAD_ASSERT_UNKNOWN(0); - } -# if CPPAD_REV_JAC_SWEEP_TRACE - for(j = 0; j < limit; j++) - z_value[j] = false; - var_sparsity.begin(i_var); - j = var_sparsity.next_element(); - while( j < limit ) - { z_value[j] = true; - j = var_sparsity.next_element(); - } - printOp( - std::cout, - play, - i_op, - i_var, - op, - arg - ); - if( NumRes(op) > 0 && op != BeginOp ) printOpResult( - std::cout, - 0, - (CppAD::vectorBool *) CPPAD_NULL, - 1, - &z_value - ); - std::cout << std::endl; - } - std::cout << std::endl; -# else - } -# endif - // values corresponding to BeginOp - CPPAD_ASSERT_UNKNOWN( i_op == 0 ); - CPPAD_ASSERT_UNKNOWN( i_var == 0 ); - - return; -} -} // END_CPPAD_NAMESPACE - -// preprocessor symbols that are local to this file -# undef CPPAD_REV_JAC_SWEEP_TRACE -# undef CPPAD_ATOMIC_CALL - -# endif diff --git a/ct_core/include/ct/external/cppad/local/rev_one.hpp b/ct_core/include/ct/external/cppad/local/rev_one.hpp deleted file mode 100644 index 087d7995b..000000000 --- a/ct_core/include/ct/external/cppad/local/rev_one.hpp +++ /dev/null @@ -1,163 +0,0 @@ -// $Id: rev_one.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_REV_ONE_HPP -# define CPPAD_REV_ONE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin RevOne$$ -$spell - dw - Taylor - const -$$ - - - - -$section First Order Derivative: Driver Routine$$ -$mindex derivative easy$$ - -$head Syntax$$ -$icode%dw% = %f%.RevOne(%x%, %i%)%$$ - - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -The syntax above sets $icode dw$$ to the -derivative of $latex F_i$$ with respect to $latex x$$; i.e., -$latex \[ -dw = -F_i^{(1)} (x) -= \left[ - \D{ F_i }{ x_0 } (x) , \cdots , \D{ F_i }{ x_{n-1} } (x) -\right] -\] $$ - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/RevOne Uses Forward/RevOne/RevOne Uses Forward/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -(see $cref/Vector/RevOne/Vector/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the derivative. - -$head i$$ -The index $icode i$$ has prototype -$codei% - size_t %i% -%$$ -and is less than $latex m$$, the dimension of the -$cref/range/seq_property/Range/$$ space for $icode f$$. -It specifies the -component of $latex F$$ that we are computing the derivative of. - -$head dw$$ -The result $icode dw$$ has prototype -$codei% - %Vector% %dw% -%$$ -(see $cref/Vector/RevOne/Vector/$$ below) -and its size is $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -The value of $icode dw$$ is the derivative of $latex F_i$$ -evaluated at $icode x$$; i.e., -for $latex j = 0 , \ldots , n - 1 $$ -$latex \[. - dw[ j ] = \D{ F_i }{ x_j } ( x ) -\] $$ - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Base$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head RevOne Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to $code RevOne$$, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0, %x%)%$$ -and the other coefficients are unspecified. - -$head Example$$ -$children% - example/rev_one.cpp -%$$ -The routine -$cref/RevOne/rev_one.cpp/$$ is both an example and test. -It returns $code true$$, if it succeeds and $code false$$ otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -template -Vector ADFun::RevOne(const Vector &x, size_t i) -{ size_t i1; - - size_t n = Domain(); - size_t m = Range(); - - // check Vector is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( - x.size() == n, - "RevOne: Length of x not equal domain dimension for f" - ); - CPPAD_ASSERT_KNOWN( - i < m, - "RevOne: the index i is not less than range dimension for f" - ); - - // point at which we are evaluating the derivative - Forward(0, x); - - // component which are are taking the derivative of - Vector w(m); - for(i1 = 0; i1 < m; i1++) - w[i1] = 0.; - w[i] = Base(1); - - // dimension the return value - Vector dw(n); - - // compute the return value - dw = Reverse(1, w); - - return dw; -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/rev_sparse_hes.hpp b/ct_core/include/ct/external/cppad/local/rev_sparse_hes.hpp deleted file mode 100644 index afe36de0e..000000000 --- a/ct_core/include/ct/external/cppad/local/rev_sparse_hes.hpp +++ /dev/null @@ -1,814 +0,0 @@ -// $Id: rev_sparse_hes.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_REV_SPARSE_HES_HPP -# define CPPAD_REV_SPARSE_HES_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin RevSparseHes$$ -$spell - std - VecAD - Jacobian - Jac - Hessian - Hes - const - Bool - Dep - proportional - var - cpp -$$ - -$section Hessian Sparsity Pattern: Reverse Mode$$ - -$head Syntax$$ -$icode%h% = %f%.RevSparseHes(%q%, %s%) -%$$ -$icode%h% = %f%.RevSparseHes(%q%, %s%, %transpose%)%$$ - - -$head Purpose$$ -We use $latex F : \B{R}^n \rightarrow \B{R}^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -For a fixed matrix $latex R \in \B{R}^{n \times q}$$ -and a fixed vector $latex S \in \B{R}^{1 \times m}$$, -we define -$latex \[ -\begin{array}{rcl} -H(x) -& = & \partial_x \left[ \partial_u S * F[ x + R * u ] \right]_{u=0} -\\ -& = & R^\R{T} * (S * F)^{(2)} ( x ) -\\ -H(x)^\R{T} -& = & (S * F)^{(2)} ( x ) * R -\end{array} -\] $$ -Given a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex R$$ and the vector $latex S$$, -$code RevSparseHes$$ returns a sparsity pattern for the $latex H(x)$$. - -$head f$$ -The object $icode f$$ has prototype -$codei% - const ADFun<%Base%> %f% -%$$ - -$head x$$ -the sparsity pattern is valid for all values of the independent -variables in $latex x \in \B{R}^n$$ -(even if it has $cref CondExp$$ or $cref VecAD$$ operations). - -$head q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of columns in $latex R \in \B{R}^{n \times q}$$ -and the number of rows in $latex H(x) \in \B{R}^{q \times n}$$. -It must be the same value as in the previous $cref ForSparseJac$$ call -$codei% - %f%.ForSparseJac(%q%, %r%, %r_transpose%) -%$$ -Note that if $icode r_transpose$$ is true, $icode r$$ in the call above -corresponding to $latex R^\R{T} \in \B{R}^{q \times n}$$ - -$head transpose$$ -The argument $icode transpose$$ has prototype -$codei% - bool %transpose% -%$$ -The default value $code false$$ is used when $icode transpose$$ is not present. - - -$head r$$ -The matrix $latex R$$ is specified by the previous call -$codei% - %f%.ForSparseJac(%q%, %r%, %transpose%) -%$$ -see $cref/r/ForSparseJac/r/$$. -The type of the elements of -$cref/VectorSet/RevSparseHes/VectorSet/$$ must be the -same as the type of the elements of $icode r$$. - -$head s$$ -The argument $icode s$$ has prototype -$codei% - const %VectorSet%& %s% -%$$ -(see $cref/VectorSet/RevSparseHes/VectorSet/$$ below) -If it has elements of type $code bool$$, -its size is $latex m$$. -If it has elements of type $code std::set$$, -its size is one and all the elements of $icode%s%[0]%$$ -are between zero and $latex m - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the vector $icode S$$. - -$head h$$ -The result $icode h$$ has prototype -$codei% - %VectorSet%& %h% -%$$ -(see $cref/VectorSet/RevSparseHes/VectorSet/$$ below). - -$subhead transpose false$$ -If $icode h$$ has elements of type $code bool$$, -its size is $latex q * n$$. -If it has elements of type $code std::set$$, -its size is $latex q$$ and all the set elements are between -zero and $icode%n%-1%$$ inclusive. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex H(x)$$. - -$subhead transpose true$$ -If $icode h$$ has elements of type $code bool$$, -its size is $latex n * q$$. -If it has elements of type $code std::set$$, -its size is $latex n$$ and all the set elements are between -zero and $icode%q%-1%$$ inclusive. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex H(x)^\R{T}$$. - -$head VectorSet$$ -The type $icode VectorSet$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code bool$$ or $code std::set$$; -see $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for a discussion -of the difference. -The type of the elements of -$cref/VectorSet/RevSparseHes/VectorSet/$$ must be the -same as the type of the elements of $icode r$$. - -$head Entire Sparsity Pattern$$ -Suppose that $latex q = n$$ and -$latex R \in \B{R}^{n \times n}$$ is the $latex n \times n$$ identity matrix. -Further suppose that the $latex S$$ is the $th k$$ -$cref/elementary vector/glossary/Elementary Vector/$$; i.e. -$latex \[ -S_j = \left\{ \begin{array}{ll} - 1 & {\rm if} \; j = k - \\ - 0 & {\rm otherwise} -\end{array} \right. -\] $$ -In this case, -the corresponding value $icode h$$ is a -sparsity pattern for the Hessian matrix -$latex F_k^{(2)} (x) \in \B{R}^{n \times n}$$. - -$head Example$$ -$children% - example/rev_sparse_hes.cpp - %example/sparsity_sub.cpp -%$$ -The file -$cref rev_sparse_hes.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. -The file -$cref/sparsity_sub.cpp/sparsity_sub.cpp/RevSparseHes/$$ -contains an example and test of using $code RevSparseHes$$ -to compute the sparsity pattern for a subset of the Hessian. - -$end ------------------------------------------------------------------------------ -*/ -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file rev_sparse_hes.hpp -Reverse mode Hessian sparsity patterns. -*/ - -// =========================================================================== -// RevSparseHesBool -/*! -Calculate Hessian sparsity patterns using reverse mode. - -The C++ source code corresponding to this operation is -\verbatim - h = f.RevSparseHes(q, s) -\endverbatim - -\tparam Base -is the base type for this recording. - -\tparam VectorSet -is a simple vector with elements of type \c bool. - -\param transpose -is true (false) if \c is is equal to \f$ H(x) \f$ (\f$ H(x)^T \f$) -where -\f[ - H(x) = R^T (S * F)^{(2)} (x) -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \a x is any argument value. - -\param q -is the value of \a q in the -by the previous call of the form -\verbatim - f.ForSparseJac(q, r) -\endverbatim -The value \c r in this call is a sparsity pattern for the matrix \f$ R \f$. - -\param s -is a vector with size \c m that specifies the sparsity pattern -for the vector \f$ S \f$, -where \c m is the number of dependent variables -corresponding to the operation sequence stored in \a play. - -\param h -the input value of \a h must be a vector with size \c q*n. -The input value of its elements does not matter. -On output, \a h is the sparsity pattern for the matrix \f$ H(x) \f$ -or \f$ H(x)^T \f$ depending on \c transpose. - -\param num_var -is the total number of variables in this recording. - -\param dep_taddr -maps dependendent variable index -to the corresponding variable in the tape. - -\param ind_taddr -maps independent variable index -to the corresponding variable in the tape. - -\param play -is the recording that defines the function we are computing the sparsity -pattern for. - -\param for_jac_sparsity -is a vector of sets containing the -the forward Jacobian sparsity pattern corresponding to -$latex R$$ for all of the variables on the tape. -*/ - -template -void RevSparseHesBool( - bool transpose , - size_t q , - const VectorSet& s , - VectorSet& h , - size_t num_var , - CppAD::vector& dep_taddr , - CppAD::vector& ind_taddr , - CppAD::player& play , - sparse_pack& for_jac_sparsity ) -{ - // temporary indices - size_t i, j; - - // check Vector is Simple VectorSet class with bool elements - CheckSimpleVector(); - - // range and domain dimensions for F - size_t m = dep_taddr.size(); - size_t n = ind_taddr.size(); - - CPPAD_ASSERT_KNOWN( - q == for_jac_sparsity.end(), - "RevSparseHes: q is not equal to its value\n" - "in the previous call to ForSparseJac with this ADFun object." - ); - CPPAD_ASSERT_KNOWN( - size_t(s.size()) == m, - "RevSparseHes: size of s is not equal to\n" - "range dimension for ADFun object." - ); - - // Array that will hold reverse Jacobian dependency flag. - // Initialize as true for the dependent variables. - pod_vector RevJac; - RevJac.extend(num_var); - for(i = 0; i < num_var; i++) - RevJac[i] = false; - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr[i] < num_var ); - RevJac[ dep_taddr[i] ] = s[i]; - } - - // vector of sets that will hold reverse Hessain values - sparse_pack rev_hes_sparsity; - rev_hes_sparsity.resize(num_var, q); - - // compute the Hessian sparsity patterns - RevHesSweep( - n, - num_var, - &play, - for_jac_sparsity, - RevJac.data(), - rev_hes_sparsity - ); - - // return values corresponding to independent variables - CPPAD_ASSERT_UNKNOWN( size_t(h.size()) == n * q ); - for(j = 0; j < n; j++) - { for(i = 0; i < q; i++) - { if( transpose ) - h[ j * q + i ] = false; - else h[ i * n + j ] = false; - } - } - - // j is index corresponding to reverse mode partial - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr[j] < num_var ); - - // ind_taddr[j] is operator taddr for j-th independent variable - CPPAD_ASSERT_UNKNOWN( ind_taddr[j] == j + 1 ); - CPPAD_ASSERT_UNKNOWN( play.GetOp( ind_taddr[j] ) == InvOp ); - - // extract the result from rev_hes_sparsity - CPPAD_ASSERT_UNKNOWN( rev_hes_sparsity.end() == q ); - rev_hes_sparsity.begin(j + 1); - i = rev_hes_sparsity.next_element(); - while( i < q ) - { if( transpose ) - h[ j * q + i ] = true; - else h[ i * n + j ] = true; - i = rev_hes_sparsity.next_element(); - } - } - - return; -} - -// =========================================================================== -// RevSparseHesSet -/*! -Calculate Hessian sparsity patterns using reverse mode. - -The C++ source code corresponding to this operation is -\verbatim - h = f.RevSparseHes(q, s) -\endverbatim - -\tparam Base -is the base type for this recording. - -\tparam VectorSet -is a simple vector with elements of type \c std::set. - -\param transpose -is true (false) if \c is is equal to \f$ H(x) \f$ (\f$ H(x)^T \f$) -where -\f[ - H(x) = R^T (S * F)^{(2)} (x) -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \a x is any argument value. - -\param q -is the value of \a q in the -by the previous call of the form -\verbatim - f.ForSparseJac(q, r) -\endverbatim -The value \c r in this call is a sparsity pattern for the matrix \f$ R \f$. - -\param s -is a vector with size \c m that specifies the sparsity pattern -for the vector \f$ S \f$, -where \c m is the number of dependent variables -corresponding to the operation sequence stored in \a play. - -\param h -If \c transpose, the input value of \a h must be a vector with size \a q. -Otherwise, its input value must have size \c n; -On input, each element of \a h must be an empty set. -On output, \a h is the sparsity pattern for the matrix \f$ H(x) \f$ -or \f$ H(x)^T \f$ depending on \c transpose. - -\param num_var -is the total number of variables in this recording. - -\param dep_taddr -maps dependendent variable index -to the corresponding variable in the tape. - -\param ind_taddr -maps independent variable index -to the corresponding variable in the tape. - -\param play -is the recording that defines the function we are computing the sparsity -pattern for. - -\param for_jac_sparsity -is a vector of sets containing the -the forward Jacobian sparsity pattern corresponding to -$latex R$$ for all of the variables on the tape. -*/ - -template -void RevSparseHesSet( - bool transpose , - size_t q , - const VectorSet& s , - VectorSet& h , - size_t num_var , - CppAD::vector& dep_taddr , - CppAD::vector& ind_taddr , - CppAD::player& play , - CPPAD_INTERNAL_SPARSE_SET& for_jac_sparsity ) -{ - // temporary indices - size_t i, j; - std::set::const_iterator itr; - - // check VectorSet is Simple Vector class with sets for elements - CheckSimpleVector, VectorSet>( - one_element_std_set(), two_element_std_set() - ); - - // range and domain dimensions for F -# ifndef NDEBUG - size_t m = dep_taddr.size(); -# endif - size_t n = ind_taddr.size(); - - CPPAD_ASSERT_KNOWN( - q == for_jac_sparsity.end(), - "RevSparseHes: q is not equal to its value\n" - "in the previous call to ForSparseJac with this ADFun object." - ); - CPPAD_ASSERT_KNOWN( - s.size() == 1, - "RevSparseHes: size of s is not equal to one." - ); - - // Array that will hold reverse Jacobian dependency flag. - // Initialize as true for the dependent variables. - pod_vector RevJac; - RevJac.extend(num_var); - for(i = 0; i < num_var; i++) - RevJac[i] = false; - itr = s[0].begin(); - while( itr != s[0].end() ) - { i = *itr++; - CPPAD_ASSERT_KNOWN( - i < m, - "RevSparseHes: an element of the set s[0] has value " - "greater than or equal m" - ); - CPPAD_ASSERT_UNKNOWN( dep_taddr[i] < num_var ); - RevJac[ dep_taddr[i] ] = true; - } - - - // vector of sets that will hold reverse Hessain values - CPPAD_INTERNAL_SPARSE_SET rev_hes_sparsity; - rev_hes_sparsity.resize(num_var, q); - - // compute the Hessian sparsity patterns - RevHesSweep( - n, - num_var, - &play, - for_jac_sparsity, - RevJac.data(), - rev_hes_sparsity - ); - - // return values corresponding to independent variables - // j is index corresponding to reverse mode partial - CPPAD_ASSERT_UNKNOWN( size_t(h.size()) == q || transpose ); - CPPAD_ASSERT_UNKNOWN( size_t(h.size()) == n || ! transpose ); - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr[j] < num_var ); - CPPAD_ASSERT_UNKNOWN( ind_taddr[j] == j + 1 ); - CPPAD_ASSERT_UNKNOWN( play.GetOp( ind_taddr[j] ) == InvOp ); - - // extract the result from rev_hes_sparsity - // and add corresponding elements to result sets in h - CPPAD_ASSERT_UNKNOWN( rev_hes_sparsity.end() == q ); - rev_hes_sparsity.begin(j+1); - i = rev_hes_sparsity.next_element(); - while( i < q ) - { if( transpose ) - h[j].insert(i); - else h[i].insert(j); - i = rev_hes_sparsity.next_element(); - } - } - - return; -} - -// =========================================================================== -// RevSparseHes - -/*! -User API for Hessian sparsity patterns using reverse mode. - -The C++ source code corresponding to this operation is -\verbatim - h = f.RevSparseHes(q, r) -\endverbatim - -\tparam Base -is the base type for this recording. - -\tparam VectorSet -is a simple vector with elements of type \c bool -or \c std::set. - -\param transpose -is true (false) if \c is is equal to \f$ H(x) \f$ (\f$ H(x)^T \f$) -where -\f[ - H(x) = R^T (S * F)^{(2)} (x) -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \a x is any argument value. - -\param q -is the value of \a q in the -by the previous call of the form -\verbatim - f.ForSparseJac(q, r, packed) -\endverbatim -The value \c r in this call is a sparsity pattern for the matrix \f$ R \f$. -The type of the element of \c r for the previous call to \c ForSparseJac -must be the same as the type of the elements of \c s. - -\param s -is a vector with size \c m that specifies the sparsity pattern -for the vector \f$ S \f$, -where \c m is the number of dependent variables -corresponding to the operation sequence stored in \a play. - -\return -If \c transpose is false (true), -the return vector is a sparsity pattern for \f$ H(x) \f$ (\f$ H(x)^T \f$). -\f[ - H(x) = R^T ( S * F)^{(2)} (x) -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \a x is any argument value. -*/ - -template -template -VectorSet ADFun::RevSparseHes( - size_t q, const VectorSet& s, bool transpose -) -{ VectorSet h; - typedef typename VectorSet::value_type Set_type; - - // Should check to make sure q is same as in previous call to - // forward sparse Jacobian. - RevSparseHesCase( - Set_type() , - transpose , - q , - s , - h - ); - - return h; -} -// =========================================================================== -// RevSparseHesCase -/*! -Private helper function for RevSparseHes(q, s). - -All of the description in the public member function RevSparseHes(q, s) -applies. - -\param set_type -is a \c bool value. This argument is used to dispatch to the proper source -code depending on the vlaue of \c VectorSet::value_type. - -\param transpose -See \c RevSparseHes(q, s). - -\param q -See \c RevSparseHes(q, s). - -\param s -See \c RevSparseHes(q, s). - -\param h -is the return value for the corresponging call to \c RevSparseJac(q, s). -*/ -template -template -void ADFun::RevSparseHesCase( - bool set_type , - bool transpose , - size_t q , - const VectorSet& s , - VectorSet& h ) -{ size_t n = Domain(); - h.resize(q * n ); - - CPPAD_ASSERT_KNOWN( - for_jac_sparse_pack_.n_set() > 0, - "RevSparseHes: previous stored call to ForSparseJac did not " - "use bool for the elements of r." - ); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_set_.n_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_pack_.n_set() == num_var_tape_ ); - - // use sparse_pack for the calculation - CppAD::RevSparseHesBool( - transpose , - q , - s , - h , - num_var_tape_ , - dep_taddr_ , - ind_taddr_ , - play_ , - for_jac_sparse_pack_ - ); -} -/*! -Private helper function for RevSparseHes(q, s). - -All of the description in the public member function RevSparseHes(q, s) -applies. - -\param set_type -is a \c std::set value. -This argument is used to dispatch to the proper source -code depending on the vlaue of \c VectorSet::value_type. - -\param transpose -See \c RevSparseHes(q, s). - -\param q -See \c RevSparseHes(q, s). - -\param s -See \c RevSparseHes(q, s). - -\param h -is the return value for the corresponging call to \c RevSparseJac(q, s). -*/ -template -template -void ADFun::RevSparseHesCase( - const std::set& set_type , - bool transpose , - size_t q , - const VectorSet& s , - VectorSet& h ) -{ size_t n = Domain(); - if( transpose ) - h.resize(n); - else h.resize(q); - - CPPAD_ASSERT_KNOWN( - for_jac_sparse_set_.n_set() > 0, - "RevSparseHes: previous stored call to ForSparseJac did not " - "use std::set for the elements of r." - ); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_pack_.n_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_set_.n_set() == num_var_tape_ ); - - // use sparse_pack for the calculation - CppAD::RevSparseHesSet( - transpose , - q , - s , - h , - num_var_tape_ , - dep_taddr_ , - ind_taddr_ , - play_ , - for_jac_sparse_set_ - ); -} -// =========================================================================== -// RevSparseHesCheckpoint -/*! -Hessian sparsity patterns calculation used by checkpoint functions. - -\tparam Base -is the base type for this recording. - -\param transpose -is true (false) h is equal to \f$ H(x) \f$ (\f$ H(x)^T \f$) -where -\f[ - H(x) = R^T (S * F)^{(2)} (x) -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \f$ x \f$ is any argument value. - -\param q -is the value of q in the by the previous call of the form -\verbatim - f.ForSparseJac(q, r) -\endverbatim -The value r in this call is a sparsity pattern for the matrix \f$ R \f$. - -\param s -is a vector with size m that specifies the sparsity pattern -for the vector \f$ S \f$, -where m is the number of dependent variables -corresponding to the operation sequence stored in play_. - -\param h -The input size and elements of h do not matter. -On output, h is the sparsity pattern for the matrix \f$ H(x) \f$ -or \f$ H(x)^T \f$ depending on transpose. - -\par Assumptions -The forward jacobian sparsity pattern must be currently stored -in this ADFUN object. -*/ -template -void ADFun::RevSparseHesCheckpoint( - size_t q , - vector& s , - bool transpose , - CPPAD_INTERNAL_SPARSE_SET& h ) -{ size_t n = Domain(); - size_t m = Range(); - - // checkpoint functions should get this right - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_pack_.n_set() == 0 ); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_set_.n_set() == num_var_tape_ ); - CPPAD_ASSERT_UNKNOWN( for_jac_sparse_set_.end() == q ); - CPPAD_ASSERT_UNKNOWN( s.size() == m ); - - // Array that holds the reverse Jacobiain dependcy flags. - // Initialize as true for dependent variables, flase for others. - pod_vector RevJac; - RevJac.extend(num_var_tape_); - for(size_t i = 0; i < num_var_tape_; i++) - RevJac[i] = false; - for(size_t i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ) - RevJac[ dep_taddr_[i] ] = s[i]; - } - - // holds reverse Hessian sparsity pattern for all variables - CPPAD_INTERNAL_SPARSE_SET rev_hes_sparsity; - rev_hes_sparsity.resize(num_var_tape_, q); - - // compute Hessian sparsity pattern for all variables - RevHesSweep( - n, - num_var_tape_, - &play_, - for_jac_sparse_set_, - RevJac.data(), - rev_hes_sparsity - ); - - // dimension the return value - if( transpose ) - h.resize(n, q); - else - h.resize(q, n); - - // j is index corresponding to reverse mode partial - for(size_t j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] < num_var_tape_ ); - - // ind_taddr_[j] is operator taddr for j-th independent variable - CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] == j + 1 ); - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == InvOp ); - - // extract the result from rev_hes_sparsity - CPPAD_ASSERT_UNKNOWN( rev_hes_sparsity.end() == q ); - rev_hes_sparsity.begin(j + 1); - size_t i = rev_hes_sparsity.next_element(); - while( i < q ) - { if( transpose ) - h.add_element(j, i); - else h.add_element(i, j); - i = rev_hes_sparsity.next_element(); - } - } -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/rev_sparse_jac.hpp b/ct_core/include/ct/external/cppad/local/rev_sparse_jac.hpp deleted file mode 100644 index e44686218..000000000 --- a/ct_core/include/ct/external/cppad/local/rev_sparse_jac.hpp +++ /dev/null @@ -1,783 +0,0 @@ -// $Id: rev_sparse_jac.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_REV_SPARSE_JAC_HPP -# define CPPAD_REV_SPARSE_JAC_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin RevSparseJac$$ -$spell - optimizer - nz - CondExpRel - std - VecAD - var - Jacobian - Jac - const - Bool - Dep - proportional -$$ - -$section Jacobian Sparsity Pattern: Reverse Mode$$ -$mindex RevSparseJac sparse$$ - - -$head Syntax$$ -$icode%s% = %f%.RevSparseJac(%q%, %r%) -%$$ -$icode%s% = %f%.RevSparseJac(%q%, %r%, %transpose%, %dependency%)%$$ - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -For a fixed matrix $latex R \in B^{q \times m}$$, -the Jacobian of $latex R * F( x )$$ -with respect to $latex x$$ is -$latex \[ - S(x) = R * F^{(1)} ( x ) -\] $$ -Given a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for $latex R$$, -$code RevSparseJac$$ returns a sparsity pattern for the $latex S(x)$$. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ - -$head x$$ -the sparsity pattern is valid for all values of the independent -variables in $latex x \in B^n$$ -(even if it has $cref CondExp$$ or $cref VecAD$$ operations). - -$head q$$ -The argument $icode q$$ has prototype -$codei% - size_t %q% -%$$ -It specifies the number of rows in -$latex R \in B^{q \times m}$$ and the -Jacobian $latex S(x) \in B^{q \times n}$$. - -$head transpose$$ -The argument $icode transpose$$ has prototype -$codei% - bool %transpose% -%$$ -The default value $code false$$ is used when $icode transpose$$ is not present. - -$head dependency$$ -The argument $icode dependency$$ has prototype -$codei% - bool %dependency% -%$$ -If $icode dependency$$ is true, -the $cref/dependency pattern/dependency.cpp/Dependency Pattern/$$ -(instead of sparsity pattern) is computed. - -$head r$$ -The argument $icode s$$ has prototype -$codei% - const %VectorSet%& %r% -%$$ -see $cref/VectorSet/RevSparseJac/VectorSet/$$ below. - -$subhead transpose false$$ -If $icode r$$ has elements of type $code bool$$, -its size is $latex q * m$$. -If it has elements of type $code std::set$$, -its size is $icode q$$ and all its set elements are between -zero and $latex m - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex R \in B^{q \times m}$$. - -$subhead transpose true$$ -If $icode r$$ has elements of type $code bool$$, -its size is $latex m * q$$. -If it has elements of type $code std::set$$, -its size is $icode m$$ and all its set elements are between -zero and $latex q - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex R^\R{T} \in B^{m \times q}$$. - -$head s$$ -The return value $icode s$$ has prototype -$codei% - %VectorSet% %s% -%$$ -see $cref/VectorSet/RevSparseJac/VectorSet/$$ below. - -$subhead transpose false$$ -If it has elements of type $code bool$$, -its size is $latex q * n$$. -If it has elements of type $code std::set$$, -its size is $icode q$$ and all its set elements are between -zero and $latex n - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex S(x) \in {q \times n}$$. - -$subhead transpose true$$ -If it has elements of type $code bool$$, -its size is $latex n * q$$. -If it has elements of type $code std::set$$, -its size is $icode n$$ and all its set elements are between -zero and $latex q - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the matrix $latex S(x)^\R{T} \in {n \times q}$$. - -$head VectorSet$$ -The type $icode VectorSet$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code bool$$ or $code std::set$$; -see $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for a discussion -of the difference. - -$head Entire Sparsity Pattern$$ -Suppose that $latex q = m$$ and -$latex R$$ is the $latex m \times m$$ identity matrix. -In this case, -the corresponding value for $icode s$$ is a -sparsity pattern for the Jacobian $latex S(x) = F^{(1)} ( x )$$. - -$head Example$$ -$children% - example/rev_sparse_jac.cpp -%$$ -The file -$cref rev_sparse_jac.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file rev_sparse_jac.hpp -Reverse mode Jacobian sparsity patterns. -*/ - -// ========================================================================= -// RevSparseJacBool -/*! -Calculate Jacobian vector of bools sparsity patterns using reverse mode. - -The C++ source code corresponding to this operation is -\verbatim - s = f.RevSparseJac(q, r) -\endverbatim - -\tparam Base -is the base type for this recording. - -\tparam VectorSet -is a simple vector class with elements of type \c bool. - -\param transpose -are the sparsity patterns transposed. - -\param dependency -Are the derivatives with respect to left and right of the expression below -considered to be non-zero: -\code - CondExpRel(left, right, if_true, if_false) -\endcode -This is used by the optimizer to obtain the correct dependency relations. - -\param q -is the number of rows in the matrix \f$ R \f$. - -\param r -is a sparsity pattern for the matrix \f$ R \f$. - -\param s -the input value of \a s must be a vector with size p*n -where \c n is the number of independent variables -corresponding to the operation sequence stored in \a play. -The input value of the components of \c s does not matter. -On output, \a s is the sparsity pattern for the matrix -\f[ - S(x) = R * F^{(1)} (x) -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \a x is any argument value. - -\param total_num_var -is the total number of variable in this recording. - -\param dep_taddr -maps dependendent variable index -to the corresponding variable in the tape. - -\param ind_taddr -maps independent variable index -to the corresponding variable in the tape. - -\param play -is the recording that defines the function we are computing the sparsity -pattern for. -*/ - -template -void RevSparseJacBool( - bool transpose , - bool dependency , - size_t q , - const VectorSet& r , - VectorSet& s , - size_t total_num_var , - CppAD::vector& dep_taddr , - CppAD::vector& ind_taddr , - CppAD::player& play ) -{ - // temporary indices - size_t i, j; - - // check VectorSet is Simple Vector class with bool elements - CheckSimpleVector(); - - // range and domain dimensions for F - size_t m = dep_taddr.size(); - size_t n = ind_taddr.size(); - - CPPAD_ASSERT_KNOWN( - q > 0, - "RevSparseJac: q is not greater than zero" - ); - CPPAD_ASSERT_KNOWN( - size_t(r.size()) == q * m, - "RevSparseJac: size of r is not equal to\n" - "q times range dimension for ADFun object." - ); - - // vector of sets that will hold the results - sparse_pack var_sparsity; - var_sparsity.resize(total_num_var, q); - - // The sparsity pattern corresponding to the dependent variables - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr[i] < total_num_var ); - if( transpose ) - { for(j = 0; j < q; j++) if( r[ i * q + j ] ) - var_sparsity.add_element( dep_taddr[i], j ); - } - else - { for(j = 0; j < q; j++) if( r[ j * m + i ] ) - var_sparsity.add_element( dep_taddr[i], j ); - } - } - - // evaluate the sparsity patterns - RevJacSweep( - dependency, - n, - total_num_var, - &play, - var_sparsity - ); - - // return values corresponding to dependent variables - CPPAD_ASSERT_UNKNOWN( size_t(s.size()) == q * n ); - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr[j] == (j+1) ); - - // ind_taddr[j] is operator taddr for j-th independent variable - CPPAD_ASSERT_UNKNOWN( play.GetOp( ind_taddr[j] ) == InvOp ); - - // extract the result from var_sparsity - if( transpose ) - { for(i = 0; i < q; i++) - s[ j * q + i ] = false; - } - else - { for(i = 0; i < q; i++) - s[ i * n + j ] = false; - } - CPPAD_ASSERT_UNKNOWN( var_sparsity.end() == q ); - var_sparsity.begin(j+1); - i = var_sparsity.next_element(); - while( i < q ) - { if( transpose ) - s[ j * q + i ] = true; - else s[ i * n + j ] = true; - i = var_sparsity.next_element(); - } - } -} -// ========================================================================= -// RevSparseJacSet -/*! -Calculate Jacobian vector of sets sparsity patterns using reverse mode. - -The C++ source code corresponding to this operation is -\verbatim - s = f.RevSparseJac(q, r) -\endverbatim - -\tparam Base -see \c RevSparseJacBool. - -\tparam VectorSet -is a simple vector class with elements of type \c std::set. - -\param transpose -see \c RevSparseJacBool. - -\param dependency -see \c RevSparseJacBool. - -\param q -see \c RevSparseJacBool. - -\param r -see \c RevSparseJacBool. - -\param s -see \c RevSparseJacBool. - -\param total_num_var -see \c RevSparseJacBool. - -\param dep_taddr -see \c RevSparseJacBool. - -\param ind_taddr -see \c RevSparseJacBool. - -\param play -see \c RevSparseJacBool. -*/ -template -void RevSparseJacSet( - bool transpose , - bool dependency , - size_t q , - const VectorSet& r , - VectorSet& s , - size_t total_num_var , - CppAD::vector& dep_taddr , - CppAD::vector& ind_taddr , - CppAD::player& play ) -{ - // temporary indices - size_t i, j; - std::set::const_iterator itr; - - // check VectorSet is Simple Vector class with sets for elements - CheckSimpleVector, VectorSet>( - one_element_std_set(), two_element_std_set() - ); - - // domain dimensions for F - size_t n = ind_taddr.size(); - size_t m = dep_taddr.size(); - - CPPAD_ASSERT_KNOWN( - q > 0, - "RevSparseJac: q is not greater than zero" - ); - CPPAD_ASSERT_KNOWN( - size_t(r.size()) == q || transpose, - "RevSparseJac: size of r is not equal to q and transpose is false." - ); - CPPAD_ASSERT_KNOWN( - size_t(r.size()) == m || ! transpose, - "RevSparseJac: size of r is not equal to m and transpose is true." - ); - - // vector of lists that will hold the results - CPPAD_INTERNAL_SPARSE_SET var_sparsity; - var_sparsity.resize(total_num_var, q); - - // The sparsity pattern corresponding to the dependent variables - if( transpose ) - { for(i = 0; i < m; i++) - { itr = r[i].begin(); - while(itr != r[i].end()) - { j = *itr++; - CPPAD_ASSERT_KNOWN( - j < q, - "RevSparseJac: transpose is true and element of the set\n" - "r[i] has value greater than or equal q." - ); - CPPAD_ASSERT_UNKNOWN( dep_taddr[i] < total_num_var ); - var_sparsity.add_element( dep_taddr[i], j ); - } - } - } - else - { for(i = 0; i < q; i++) - { itr = r[i].begin(); - while(itr != r[i].end()) - { j = *itr++; - CPPAD_ASSERT_KNOWN( - j < m, - "RevSparseJac: transpose is false and element of the set\n" - "r[i] has value greater than or equal range dimension." - ); - CPPAD_ASSERT_UNKNOWN( dep_taddr[j] < total_num_var ); - var_sparsity.add_element( dep_taddr[j], i ); - } - } - } - // evaluate the sparsity patterns - RevJacSweep( - dependency, - n, - total_num_var, - &play, - var_sparsity - ); - - // return values corresponding to dependent variables - CPPAD_ASSERT_UNKNOWN( size_t(s.size()) == q || transpose ); - CPPAD_ASSERT_UNKNOWN( size_t(s.size()) == n || ! transpose ); - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr[j] == (j+1) ); - - // ind_taddr[j] is operator taddr for j-th independent variable - CPPAD_ASSERT_UNKNOWN( play.GetOp( ind_taddr[j] ) == InvOp ); - - CPPAD_ASSERT_UNKNOWN( var_sparsity.end() == q ); - var_sparsity.begin(j+1); - i = var_sparsity.next_element(); - while( i < q ) - { if( transpose ) - s[j].insert(i); - else s[i].insert(j); - i = var_sparsity.next_element(); - } - } -} -// ========================================================================= -// RevSparseJacCase - -/*! -Private helper function for \c RevSparseJac(q, r, transpose). - -All of the description in the public member function -\c RevSparseJac(q, r, transpose) apply. - -\param set_type -is a \c bool value. -This argument is used to dispatch to the proper source code -depending on the value of \c VectorSet::value_type. - -\param transpose -See \c RevSparseJac(q, r, transpose, dependency) - -\param dependency -See \c RevSparseJac(q, r, transpose, dependency) - -\param q -See \c RevSparseJac(q, r, transpose, dependency) - -\param r -See \c RevSparseJac(q, r, transpose, dependency) - -\param s -is the return value for the corresponding call to -RevSparseJac(q, r, transpose). -*/ - -template -template -void ADFun::RevSparseJacCase( - bool set_type , - bool transpose , - bool dependency , - size_t q , - const VectorSet& r , - VectorSet& s ) -{ size_t n = Domain(); - - // dimension of the result vector - s.resize( q * n ); - - // store results in s - RevSparseJacBool( - transpose , - dependency , - q , - r , - s , - num_var_tape_ , - dep_taddr_ , - ind_taddr_ , - play_ - ); -} - -/*! -Private helper function for \c RevSparseJac(q, r, transpose). - -All of the description in the public member function -\c RevSparseJac(q, r, transpose) apply. - -\param set_type -is a \c std::set object. -This argument is used to dispatch to the proper source code -depending on the value of \c VectorSet::value_type. - -\param transpose -See \c RevSparseJac(q, r, transpose, dependency) - -\param dependency -See \c RevSparseJac(q, r, transpose, dependency) - -\param q -See \c RevSparseJac(q, r, transpose, dependency) - -\param r -See \c RevSparseJac(q, r, transpose, dependency) - -\param s -is the return value for the corresponding call to RevSparseJac(q, r, transpose) -*/ - -template -template -void ADFun::RevSparseJacCase( - const std::set& set_type , - bool transpose , - bool dependency , - size_t q , - const VectorSet& r , - VectorSet& s ) -{ // dimension of the result vector - if( transpose ) - s.resize( Domain() ); - else s.resize( q ); - - // store results in r - RevSparseJacSet( - transpose , - dependency , - q , - r , - s , - num_var_tape_ , - dep_taddr_ , - ind_taddr_ , - play_ - ); -} -// ========================================================================= -// RevSparseJac -/*! -User API for Jacobian sparsity patterns using reverse mode. - -The C++ source code corresponding to this operation is -\verbatim - s = f.RevSparseJac(q, r, transpose, dependency) -\endverbatim - -\tparam Base -is the base type for this recording. - -\tparam VectorSet -is a simple vector with elements of type \c bool. -or \c std::set. - -\param q -is the number of rows in the matrix \f$ R \f$. - -\param r -is a sparsity pattern for the matrix \f$ R \f$. - -\param transpose -are the sparsity patterns for \f$ R \f$ and \f$ S(x) \f$ transposed. - -\param dependency -Are the derivatives with respect to left and right of the expression below -considered to be non-zero: -\code - CondExpRel(left, right, if_true, if_false) -\endcode -This is used by the optimizer to obtain the correct dependency relations. - - -\return -If \c transpose is false (true), the return value is a sparsity pattern -for \f$ S(x) \f$ (\f$ S(x)^T \f$) where -\f[ - S(x) = R * F^{(1)} (x) -\f] -and \f$ F \f$ is the function corresponding to the operation sequence -and \a x is any argument value. -If \c VectorSet::value_type is \c bool, -the return value has size \f$ q * n \f$ ( \f$ n * q \f$). -If \c VectorSet::value_type is \c std::set, -the return value has size \f$ q \f$ ( \f$ n \f$) -and with all its elements between zero and \f$ n - 1 \f$ (\f$ q - 1 \f$). -*/ -template -template -VectorSet ADFun::RevSparseJac( - size_t q , - const VectorSet& r , - bool transpose , - bool dependency ) -{ - VectorSet s; - typedef typename VectorSet::value_type Set_type; - - RevSparseJacCase( - Set_type() , - transpose , - dependency , - q , - r , - s - ); - return s; -} -// =========================================================================== -// RevSparseJacCheckpoint -/*! -Reverse mode Jacobian sparsity calculation used by checkpoint functions. - -\tparam Base -is the base type for this recording. - -\param transpose -is true (false) s is equal to \f$ S(x) \f$ (\f$ S(x)^T \f$) -where -\f[ - S(x) = R * F^{(1)} (x) -\f] -where \f$ F \f$ is the function corresponding to the operation sequence -and \f$ x \f$ is any argument value. - -\param q -is the number of rows in the matrix \f$ R \f$. - -\param r -is a sparsity pattern for the matrix \f$ R \f$. - -\param transpose -are the sparsity patterns for \f$ R \f$ and \f$ S(x) \f$ transposed. - -\param dependency -Are the derivatives with respect to left and right of the expression below -considered to be non-zero: -\code - CondExpRel(left, right, if_true, if_false) -\endcode -This is used by the optimizer to obtain the correct dependency relations. - -\param s -The input size and elements of s do not matter. -On output, s is the sparsity pattern for the matrix \f$ S(x) \f$ -or \f$ S(x)^T \f$ depending on transpose. - -*/ -template -void ADFun::RevSparseJacCheckpoint( - size_t q , - CPPAD_INTERNAL_SPARSE_SET& r , - bool transpose , - bool dependency , - CPPAD_INTERNAL_SPARSE_SET& s ) -{ size_t n = Domain(); - size_t m = Range(); - -# ifndef NDEBUG - if( transpose ) - { CPPAD_ASSERT_UNKNOWN( r.n_set() == m ); - CPPAD_ASSERT_UNKNOWN( r.end() == q ); - } - else - { CPPAD_ASSERT_UNKNOWN( r.n_set() == q ); - CPPAD_ASSERT_UNKNOWN( r.end() == m ); - } - for(size_t i = 0; i < m; i++) - CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); -# endif - - // holds reverse Jacobian sparsity pattern for all variables - CPPAD_INTERNAL_SPARSE_SET var_sparsity; - var_sparsity.resize(num_var_tape_, q); - - // set sparsity pattern for dependent variables - if( transpose ) - { for(size_t i = 0; i < m; i++) - { r.begin(i); - size_t j = r.next_element(); - while( j < q ) - { var_sparsity.add_element( dep_taddr_[i], j ); - j = r.next_element(); - } - } - } - else - { for(size_t j = 0; j < q; j++) - { r.begin(j); - size_t i = r.next_element(); - while( i < m ) - { var_sparsity.add_element( dep_taddr_[i], j ); - i = r.next_element(); - } - } - } - - // evaluate the sparsity pattern for all variables - RevJacSweep( - dependency, - n, - num_var_tape_, - &play_, - var_sparsity - ); - - // dimension the return value - if( transpose ) - s.resize(n, m); - else - s.resize(m, n); - - // return values corresponding to independent variables - for(size_t j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] == (j+1) ); - - // ind_taddr_[j] is operator taddr for j-th independent variable - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == InvOp ); - - // extract the result from var_sparsity - CPPAD_ASSERT_UNKNOWN( var_sparsity.end() == q ); - var_sparsity.begin(j+1); - size_t i = var_sparsity.next_element(); - while( i < q ) - { if( transpose ) - s.add_element(j, i); - else - s.add_element(i, j); - i = var_sparsity.next_element(); - } - } - -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/rev_two.hpp b/ct_core/include/ct/external/cppad/local/rev_two.hpp deleted file mode 100644 index 3eb4b3316..000000000 --- a/ct_core/include/ct/external/cppad/local/rev_two.hpp +++ /dev/null @@ -1,236 +0,0 @@ -// $Id: rev_two.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_REV_TWO_HPP -# define CPPAD_REV_TWO_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin RevTwo$$ -$spell - ddw - typename - Taylor - const -$$ - - - - - -$section Reverse Mode Second Partial Derivative Driver$$ -$mindex order easy$$ - -$head Syntax$$ -$icode%ddw% = %f%.RevTwo(%x%, %i%, %j%)%$$ - - -$head Purpose$$ -We use $latex F : B^n \rightarrow B^m$$ to denote the -$cref/AD function/glossary/AD Function/$$ corresponding to $icode f$$. -The syntax above sets -$latex \[ - ddw [ k * p + \ell ] - = - \DD{ F_{i[ \ell ]} }{ x_{j[ \ell ]} }{ x_k } (x) -\] $$ -for $latex k = 0 , \ldots , n-1$$ -and $latex \ell = 0 , \ldots , p$$, -where $latex p$$ is the size of the vectors $icode i$$ and $icode j$$. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/RevTwo Uses Forward/RevTwo/RevTwo Uses Forward/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %VectorBase% &%x% -%$$ -(see $cref/VectorBase/RevTwo/VectorBase/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the partial derivatives listed above. - -$head i$$ -The argument $icode i$$ has prototype -$codei% - const %VectorSize_t% &%i% -%$$ -(see $cref/VectorSize_t/RevTwo/VectorSize_t/$$ below) -We use $icode p$$ to denote the size of the vector $icode i$$. -All of the indices in $icode i$$ -must be less than $icode m$$, the dimension of the -$cref/range/seq_property/Range/$$ space for $icode f$$; i.e., -for $latex \ell = 0 , \ldots , p-1$$, $latex i[ \ell ] < m$$. - -$head j$$ -The argument $icode j$$ has prototype -$codei% - const %VectorSize_t% &%j% -%$$ -(see $cref/VectorSize_t/RevTwo/VectorSize_t/$$ below) -and its size must be equal to $icode p$$, -the size of the vector $icode i$$. -All of the indices in $icode j$$ -must be less than $icode n$$; i.e., -for $latex \ell = 0 , \ldots , p-1$$, $latex j[ \ell ] < n$$. - -$head ddw$$ -The result $icode ddw$$ has prototype -$codei% - %VectorBase% %ddw% -%$$ -(see $cref/VectorBase/RevTwo/VectorBase/$$ below) -and its size is $latex n * p$$. -It contains the requested partial derivatives; to be specific, -for $latex k = 0 , \ldots , n - 1 $$ -and $latex \ell = 0 , \ldots , p - 1$$ -$latex \[ - ddw [ k * p + \ell ] - = - \DD{ F_{i[ \ell ]} }{ x_{j[ \ell ]} }{ x_k } (x) -\] $$ - -$head VectorBase$$ -The type $icode VectorBase$$ must be a $cref SimpleVector$$ class with -$cref/elements of type Base/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head VectorSize_t$$ -The type $icode VectorSize_t$$ must be a $cref SimpleVector$$ class with -$cref/elements of type size_t/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head RevTwo Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to $code RevTwo$$, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0, %x%)%$$ -and the other coefficients are unspecified. - -$head Examples$$ -$children% - example/rev_two.cpp -%$$ -The routine -$cref/RevTwo/rev_two.cpp/$$ is both an example and test. -It returns $code true$$, if it succeeds and $code false$$ otherwise. - -$end ------------------------------------------------------------------------------ -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -template -VectorBase ADFun::RevTwo( - const VectorBase &x, - const VectorSize_t &i, - const VectorSize_t &j) -{ size_t i1; - size_t j1; - size_t k; - size_t l; - - size_t n = Domain(); - size_t m = Range(); - size_t p = i.size(); - - // check VectorBase is Simple Vector class with Base elements - CheckSimpleVector(); - - // check VectorSize_t is Simple Vector class with size_t elements - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( - x.size() == n, - "RevTwo: Length of x not equal domain dimension for f." - ); - CPPAD_ASSERT_KNOWN( - i.size() == j.size(), - "RevTwo: Lenght of the i and j vectors are not equal." - ); - // point at which we are evaluating the second partials - Forward(0, x); - - // dimension the return value - VectorBase ddw(n * p); - - // direction vector in argument space - VectorBase dx(n); - for(j1 = 0; j1 < n; j1++) - dx[j1] = Base(0); - - // direction vector in range space - VectorBase w(m); - for(i1 = 0; i1 < m; i1++) - w[i1] = Base(0); - - // place to hold the results of a reverse calculation - VectorBase r(n * 2); - - // check the indices in i and j - for(l = 0; l < p; l++) - { i1 = i[l]; - j1 = j[l]; - CPPAD_ASSERT_KNOWN( - i1 < m, - "RevTwo: an eleemnt of i not less than range dimension for f." - ); - CPPAD_ASSERT_KNOWN( - j1 < n, - "RevTwo: an element of j not less than domain dimension for f." - ); - } - - // loop over all forward directions - for(j1 = 0; j1 < n; j1++) - { // first order forward mode calculation done - bool first_done = false; - for(l = 0; l < p; l++) if( j[l] == j1 ) - { if( ! first_done ) - { first_done = true; - - // first order forward mode in j1 direction - dx[j1] = Base(1); - Forward(1, dx); - dx[j1] = Base(0); - } - // execute a reverse in this component direction - i1 = i[l]; - w[i1] = Base(1); - r = Reverse(2, w); - w[i1] = Base(0); - - // place the reverse result in return value - for(k = 0; k < n; k++) - ddw[k * p + l] = r[k * 2 + 1]; - } - } - return ddw; -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/reverse.hpp b/ct_core/include/ct/external/cppad/local/reverse.hpp deleted file mode 100644 index 1de5093c7..000000000 --- a/ct_core/include/ct/external/cppad/local/reverse.hpp +++ /dev/null @@ -1,209 +0,0 @@ -// $Id: reverse.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_REVERSE_HPP -# define CPPAD_REVERSE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file reverse.hpp -Compute derivatives using reverse mode. -*/ - - -/*! -Use reverse mode to compute derivative of forward mode Taylor coefficients. - -The function -\f$ X : {\rm R} \times {\rm R}^{n \times q} \rightarrow {\rm R} \f$ -is defined by -\f[ -X(t , u) = \sum_{k=0}^{q-1} u^{(k)} t^k -\f] -The function -\f$ Y : {\rm R} \times {\rm R}^{n \times q} \rightarrow {\rm R} \f$ -is defined by -\f[ -Y(t , u) = F[ X(t, u) ] -\f] -The function -\f$ W : {\rm R}^{n \times q} \rightarrow {\rm R} \f$ is defined by -\f[ -W(u) = \sum_{k=0}^{q-1} ( w^{(k)} )^{\rm T} -\frac{1}{k !} \frac{ \partial^k } { t^k } Y(0, u) -\f] - -\tparam Base -base type for the operator; i.e., this operation sequence was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\tparam VectorBase -is a Simple Vector class with elements of type \a Base. - -\param q -is the number of the number of Taylor coefficients that are being -differentiated (per variable). - -\param w -is the weighting for each of the Taylor coefficients corresponding -to dependent variables. -If the argument \a w has size m * q , -for \f$ k = 0 , \ldots , q-1 \f$ and \f$ i = 0, \ldots , m-1 \f$, -\f[ - w_i^{(k)} = w [ i * q + k ] -\f] -If the argument \a w has size \c m , -for \f$ k = 0 , \ldots , q-1 \f$ and \f$ i = 0, \ldots , m-1 \f$, -\f[ -w_i^{(k)} = \left\{ \begin{array}{ll} - w [ i ] & {\rm if} \; k = q-1 - \\ - 0 & {\rm otherwise} -\end{array} \right. -\f] - -\return -Is a vector \f$ dw \f$ such that -for \f$ j = 0 , \ldots , n-1 \f$ and -\f$ k = 0 , \ldots , q-1 \f$ -\f[ - dw[ j * q + k ] = W^{(1)} ( x )_{j,k} -\f] -where the matrix \f$ x \f$ is the value for \f$ u \f$ -that corresponding to the forward mode Taylor coefficients -for the independent variables as specified by previous calls to Forward. - -*/ -template -template -VectorBase ADFun::Reverse(size_t q, const VectorBase &w) -{ // constants - const Base zero(0); - - // temporary indices - size_t i, j, k; - - // number of independent variables - size_t n = ind_taddr_.size(); - - // number of dependent variables - size_t m = dep_taddr_.size(); - - pod_vector Partial; - Partial.extend(num_var_tape_ * q); - - // update maximum memory requirement - // memoryMax = std::max( memoryMax, - // Memory() + num_var_tape_ * q * sizeof(Base) - // ); - - // check VectorBase is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( - size_t(w.size()) == m || size_t(w.size()) == (m * q), - "Argument w to Reverse does not have length equal to\n" - "the dimension of the range for the corresponding ADFun." - ); - CPPAD_ASSERT_KNOWN( - q > 0, - "The first argument to Reverse must be greater than zero." - ); - CPPAD_ASSERT_KNOWN( - num_order_taylor_ >= q, - "Less that q taylor_ coefficients are currently stored" - " in this ADFun object." - ); - // special case where multiple forward directions have been computed, - // but we are only using the one direction zero order results - if( (q == 1) & (num_direction_taylor_ > 1) ) - { num_order_taylor_ = 1; // number of orders to copy - size_t c = cap_order_taylor_; // keep the same capacity setting - size_t r = 1; // only keep one direction - capacity_order(c, r); - } - CPPAD_ASSERT_KNOWN( - num_direction_taylor_ == 1, - "Reverse mode for Forward(q, r, xq) with more than one direction" - "\n(r > 1) is not yet supported for q > 1." - ); - // initialize entire Partial matrix to zero - for(i = 0; i < num_var_tape_; i++) - for(j = 0; j < q; j++) - Partial[i * q + j] = zero; - - // set the dependent variable direction - // (use += because two dependent variables can point to same location) - for(i = 0; i < m; i++) - { CPPAD_ASSERT_UNKNOWN( dep_taddr_[i] < num_var_tape_ ); - if( size_t(w.size()) == m ) - Partial[dep_taddr_[i] * q + q - 1] += w[i]; - else - { for(k = 0; k < q; k++) - // ? should use += here, first make test to demonstrate bug - Partial[ dep_taddr_[i] * q + k ] = w[i * q + k ]; - } - } - - // evaluate the derivatives - CPPAD_ASSERT_UNKNOWN( cskip_op_.size() == play_.num_op_rec() ); - CPPAD_ASSERT_UNKNOWN( load_op_.size() == play_.num_load_op_rec() ); - ReverseSweep( - q - 1, - n, - num_var_tape_, - &play_, - cap_order_taylor_, - taylor_.data(), - q, - Partial.data(), - cskip_op_.data(), - load_op_ - ); - - // return the derivative values - VectorBase value(n * q); - for(j = 0; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( ind_taddr_[j] < num_var_tape_ ); - - // independent variable taddr equals its operator taddr - CPPAD_ASSERT_UNKNOWN( play_.GetOp( ind_taddr_[j] ) == InvOp ); - - // by the Reverse Identity Theorem - // partial of y^{(k)} w.r.t. u^{(0)} is equal to - // partial of y^{(q-1)} w.r.t. u^{(q - 1 - k)} - if( size_t(w.size()) == m ) - { for(k = 0; k < q; k++) - value[j * q + k ] = - Partial[ind_taddr_[j] * q + q - 1 - k]; - } - else - { for(k = 0; k < q; k++) - value[j * q + k ] = - Partial[ind_taddr_[j] * q + k]; - } - } - CPPAD_ASSERT_KNOWN( ! ( hasnan(value) && check_for_nan_ ) , - "dw = f.Reverse(q, w): has a nan,\n" - "but none of its Taylor coefficents are nan." - ); - - return value; -} - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/reverse_sweep.hpp b/ct_core/include/ct/external/cppad/local/reverse_sweep.hpp deleted file mode 100644 index cd02a07c3..000000000 --- a/ct_core/include/ct/external/cppad/local/reverse_sweep.hpp +++ /dev/null @@ -1,837 +0,0 @@ -// $Id: reverse_sweep.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_REVERSE_SWEEP_HPP -# define CPPAD_REVERSE_SWEEP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file reverse_sweep.hpp -Compute derivatives of arbitrary order Taylor coefficients. -*/ - -/* -\def CPPAD_ATOMIC_CALL -This avoids warnings when NDEBUG is defined and user_ok is not used. -If \c NDEBUG is defined, this resolves to -\code - user_atom->reverse -\endcode -otherwise, it respolves to -\code - user_ok = user_atom->reverse -\endcode -This maco is undefined at the end of this file to facillitate is -use with a different definition in other files. -*/ -# ifdef NDEBUG -# define CPPAD_ATOMIC_CALL user_atom->reverse -# else -# define CPPAD_ATOMIC_CALL user_ok = user_atom->reverse -# endif - -/*! -\def CPPAD_REVERSE_SWEEP_TRACE -This value is either zero or one. -Zero is the normal operational value. -If it is one, a trace of every reverse_sweep computation is printed. -*/ -# define CPPAD_REVERSE_SWEEP_TRACE 0 - -/*! -Compute derivative of arbitrary order forward mode Taylor coefficients. - -\tparam Base -base type for the operator; i.e., this operation sequence was recorded -using AD< \a Base > and computations by this routine are done using type -\a Base. - -\param d -is the highest order Taylor coefficients that -we are computing the derivative of. - -\param n -is the number of independent variables on the tape. - -\param numvar -is the total number of variables on the tape. -This is also equal to the number of rows in the matrix \a Taylor; i.e., -play->num_var_rec(). - -\param play -The information stored in \a play -is a recording of the operations corresponding to the function -\f[ - F : {\bf R}^n \rightarrow {\bf R}^m -\f] -where \f$ n \f$ is the number of independent variables and -\f$ m \f$ is the number of dependent variables. -We define \f$ u^{(k)} \f$ as the value of x_k in the previous call -of the form - - f.Forward(k, x_k) - -We define -\f$ X : {\bf R}^{n \times d} \rightarrow {\bf R}^n \f$ by -\f[ - X(t, u) = u^{(0)} + u^{(1)} t + \cdots + u^{(d)} t^d -\f] -We define -\f$ Y : {\bf R}^{n \times d} \rightarrow {\bf R}^m \f$ by -\f[ - Y(t, u) = F[ X(t, u) ] -\f] -We define the function -\f$ W : {\bf R}^{n \times d} \rightarrow {\bf R} \f$ by -\f[ -W(u) -= -\sum_{k=0}^{d} ( w^{(k)} )^{\rm T} - \frac{1}{k !} \frac{\partial^k}{\partial t^k} Y(0, u) -\f] -(The matrix \f$ w \in {\bf R}^m \f$, -is defined below under the heading Partial.) -Note that the scale factor 1 / k converts -the k-th partial derivative to the k-th order Taylor coefficient. -This routine computes the derivative of \f$ W(u) \f$ -with respect to all the Taylor coefficients -\f$ u^{(k)} \f$ for \f$ k = 0 , ... , d \f$. -\n -\n -The object \a play is effectly constant. -There is an exception to this, -while palying back the tape -the object \a play holds information about the current location -with in the tape and this changes during palyback. - -\param J -Is the number of columns in the coefficient matrix \a Taylor. -This must be greater than or equal \a d + 1. - -\param Taylor -For i = 1 , ... , \a numvar, and for k = 0 , ... , \a d, -\a Taylor [ i * J + k ] -is the k-th order Taylor coefficient corresponding to -variable with index i on the tape. -The value \f$ u \in {\bf R}^{n \times d} \f$, -at which the derivative is computed, -is defined by -\f$ u_j^{(k)} \f$ = \a Taylor [ j * J + k ] -for j = 1 , ... , \a n, and for k = 0 , ... , \a d. - -\param K -Is the number of columns in the partial derivative matrix \a Partial. -It must be greater than or equal \a d + 1. - -\param Partial -\b Input: -The last \f$ m \f$ rows of \a Partial are inputs. -The matrix \f$ w \f$, used to define \f$ W(u) \f$, -is specified by these rows. -For i = 0 , ... , m - 1, -for k = 0 , ... , d, -Partial [ (numvar - m + i ) * K + k ] = w[i,k]. -\n -\n -\b Temporary: -For i = n+1 , ... , \a numvar - 1 and for k = 0 , ... , d, -the value of \a Partial [ i * K + k ] is used for temporary work space -and its output value is not defined. -\n -\n -\b Output: -For j = 1 , ... , n and for k = 0 , ... , d, -\a Partial [ j * K + k ] -is the partial derivative of \f$ W( u ) \f$ with -respect to \f$ u_j^{(k)} \f$. - -\param cskip_op -Is a vector with size play->num_op_rec(). -If cskip_op[i] is true, the operator index i in the recording -does not affect any of the dependent variable (given the value -of the independent variables). - -\param var_by_load_op -is a vector with size play->num_load_op_rec(). -Is the variable index corresponding to each load instruction. -In the case where the index is zero, -the instruction corresponds to a parameter (not variable). - -\par Assumptions -The first operator on the tape is a BeginOp, -and the next \a n operators are InvOp operations for the -corresponding independent variables. -*/ -template -void ReverseSweep( - size_t d, - size_t n, - size_t numvar, - player* play, - size_t J, - const Base* Taylor, - size_t K, - Base* Partial, - bool* cskip_op, - const pod_vector& var_by_load_op -) -{ - OpCode op; - size_t i_op; - size_t i_var; - - const addr_t* arg = CPPAD_NULL; - - // check numvar argument - CPPAD_ASSERT_UNKNOWN( play->num_var_rec() == numvar ); - CPPAD_ASSERT_UNKNOWN( numvar > 0 ); - - // length of the parameter vector (used by CppAD assert macros) - const size_t num_par = play->num_par_rec(); - - // pointer to the beginning of the parameter vector - const Base* parameter = CPPAD_NULL; - if( num_par > 0 ) - parameter = play->GetPar(); - - // work space used by UserOp. - const size_t user_k = d; // highest order we are differentiating - const size_t user_k1 = d+1; // number of orders for this calculation - vector user_ix; // variable indices for argument vector - vector user_tx; // argument vector Taylor coefficients - vector user_ty; // result vector Taylor coefficients - vector user_px; // partials w.r.t argument vector - vector user_py; // partials w.r.t. result vector - size_t user_index = 0; // indentifier for this atomic operation - size_t user_id = 0; // user identifier for this call to operator - size_t user_i = 0; // index in result vector - size_t user_j = 0; // index in argument vector - size_t user_m = 0; // size of result vector - size_t user_n = 0; // size of arugment vector - // - atomic_base* user_atom = CPPAD_NULL; // user's atomic op calculator -# ifndef NDEBUG - bool user_ok = false; // atomic op return value -# endif - // - // next expected operator in a UserOp sequence - enum { user_start, user_arg, user_ret, user_end } user_state = user_end; - - // temporary indices - size_t j, ell; - - // Initialize - play->reverse_start(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN( op == EndOp ); -# if CPPAD_REVERSE_SWEEP_TRACE - std::cout << std::endl; -# endif - bool more_operators = true; - while(more_operators) - { // next op - play->reverse_next(op, arg, i_op, i_var); - CPPAD_ASSERT_UNKNOWN((i_op > n) | (op == InvOp) | (op == BeginOp)); - CPPAD_ASSERT_UNKNOWN((i_op <= n) | (op != InvOp) | (op != BeginOp)); - CPPAD_ASSERT_UNKNOWN( i_op < play->num_op_rec() ); - - // check if we are skipping this operation - while( cskip_op[i_op] ) - { if( op == CSumOp ) - { // CSumOp has a variable number of arguments - play->reverse_csum(op, arg, i_op, i_var); - } - CPPAD_ASSERT_UNKNOWN( op != CSkipOp ); - // if( op == CSkipOp ) - // { // CSkip has a variable number of arguments - // play->reverse_cskip(op, arg, i_op, i_var); - // } - CPPAD_ASSERT_UNKNOWN( i_op < play->num_op_rec() ); - play->reverse_next(op, arg, i_op, i_var); - } - - // rest of informaiton depends on the case -# if CPPAD_REVERSE_SWEEP_TRACE - if( op == CSumOp ) - { // CSumOp has a variable number of arguments - play->reverse_csum(op, arg, i_op, i_var); - } - if( op == CSkipOp ) - { // CSkip has a variable number of arguments - play->reverse_cskip(op, arg, i_op, i_var); - } - size_t i_tmp = i_var; - const Base* Z_tmp = Taylor + i_var * J; - const Base* pZ_tmp = Partial + i_var * K; - printOp( - std::cout, - play, - i_op, - i_tmp, - op, - arg - ); - if( NumRes(op) > 0 && op != BeginOp ) printOpResult( - std::cout, - d + 1, - Z_tmp, - d + 1, - pZ_tmp - ); - std::cout << std::endl; -# endif - switch( op ) - { - - case AbsOp: - reverse_abs_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case AcosOp: - // sqrt(1 - x * x), acos(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - reverse_acos_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AcoshOp: - // sqrt(x * x - 1), acosh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - reverse_acosh_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; -# endif - // -------------------------------------------------- - - case AddvvOp: - reverse_addvv_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case AddpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - reverse_addpv_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case AsinOp: - // sqrt(1 - x * x), asin(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - reverse_asin_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AsinhOp: - // sqrt(1 + x * x), asinh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - reverse_asinh_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; -# endif - // -------------------------------------------------- - - case AtanOp: - // 1 + x * x, atan(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - reverse_atan_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; - // ------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case AtanhOp: - // 1 - x * x, atanh(x) - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - reverse_atanh_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; -# endif - // ------------------------------------------------- - - case BeginOp: - CPPAD_ASSERT_NARG_NRES(op, 1, 1); - more_operators = false; - break; - // -------------------------------------------------- - - case CSkipOp: - // CSkipOp has a variable number of arguments and - // forward_next thinks it one has one argument. - // we must inform reverse_next of this special case. -# if ! CPPAD_REVERSE_SWEEP_TRACE - play->reverse_cskip(op, arg, i_op, i_var); -# endif - break; - // ------------------------------------------------- - - case CSumOp: - // CSumOp has a variable number of arguments and - // reverse_next thinks it one has one argument. - // We must inform reverse_next of this special case. -# if ! CPPAD_REVERSE_SWEEP_TRACE - play->reverse_csum(op, arg, i_op, i_var); -# endif - reverse_csum_op( - d, i_var, arg, K, Partial - ); - // end of a cummulative summation - break; - // ------------------------------------------------- - - case CExpOp: - reverse_cond_op( - d, - i_var, - arg, - num_par, - parameter, - J, - Taylor, - K, - Partial - ); - break; - // -------------------------------------------------- - - case CosOp: - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - reverse_cos_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case CoshOp: - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - reverse_cosh_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case DisOp: - // Derivative of discrete operation is zero so no - // contribution passes through this operation. - break; - // -------------------------------------------------- - - case DivvvOp: - reverse_divvv_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case DivpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - reverse_divpv_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case DivvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - reverse_divvp_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case ErfOp: - reverse_erf_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; -# endif - // -------------------------------------------------- - - case ExpOp: - reverse_exp_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case Expm1Op: - reverse_expm1_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; -# endif - // -------------------------------------------------- - - case InvOp: - break; - // -------------------------------------------------- - - case LdpOp: - reverse_load_op( - op, d, i_var, arg, J, Taylor, K, Partial, var_by_load_op.data() - ); - break; - // ------------------------------------------------- - - case LdvOp: - reverse_load_op( - op, d, i_var, arg, J, Taylor, K, Partial, var_by_load_op.data() - ); - break; - // -------------------------------------------------- - - case EqpvOp: - case EqvvOp: - case LtpvOp: - case LtvpOp: - case LtvvOp: - case LepvOp: - case LevpOp: - case LevvOp: - case NepvOp: - case NevvOp: - break; - // ------------------------------------------------- - - case LogOp: - reverse_log_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - -# if CPPAD_USE_CPLUSPLUS_2011 - case Log1pOp: - reverse_log1p_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; -# endif - // -------------------------------------------------- - - case MulpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - reverse_mulpv_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case MulvvOp: - reverse_mulvv_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case ParOp: - break; - // -------------------------------------------------- - - case PowvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - reverse_powvp_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // ------------------------------------------------- - - case PowpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - reverse_powpv_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // ------------------------------------------------- - - case PowvvOp: - reverse_powvv_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case PriOp: - // no result so nothing to do - break; - // -------------------------------------------------- - - case SignOp: - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - reverse_sign_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; - // ------------------------------------------------- - - case SinOp: - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - reverse_sin_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; - // ------------------------------------------------- - - case SinhOp: - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - reverse_sinh_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case SqrtOp: - reverse_sqrt_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case StppOp: - break; - // -------------------------------------------------- - - case StpvOp: - break; - // ------------------------------------------------- - - case StvpOp: - break; - // ------------------------------------------------- - - case StvvOp: - break; - // -------------------------------------------------- - - case SubvvOp: - reverse_subvv_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case SubpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - reverse_subpv_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case SubvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - reverse_subvp_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // ------------------------------------------------- - - case TanOp: - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - reverse_tan_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; - // ------------------------------------------------- - - case TanhOp: - CPPAD_ASSERT_UNKNOWN( i_var < numvar ); - reverse_tanh_op( - d, i_var, arg[0], J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case UserOp: - // start or end an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( NumRes( UserOp ) == 0 ); - CPPAD_ASSERT_UNKNOWN( NumArg( UserOp ) == 4 ); - if( user_state == user_end ) - { user_index = arg[0]; - user_id = arg[1]; - user_n = arg[2]; - user_m = arg[3]; - user_atom = atomic_base::class_object(user_index); -# ifndef NDEBUG - if( user_atom == CPPAD_NULL ) - { std::string msg = - atomic_base::class_name(user_index) - + ": atomic_base function has been deleted"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - if(user_ix.size() != user_n) - user_ix.resize(user_n); - if(user_tx.size() != user_n * user_k1) - { user_tx.resize(user_n * user_k1); - user_px.resize(user_n * user_k1); - } - if(user_ty.size() != user_m * user_k1) - { user_ty.resize(user_m * user_k1); - user_py.resize(user_m * user_k1); - } - user_j = user_n; - user_i = user_m; - user_state = user_ret; - } - else - { CPPAD_ASSERT_UNKNOWN( user_state == user_start ); - CPPAD_ASSERT_UNKNOWN( user_index == size_t(arg[0]) ); - CPPAD_ASSERT_UNKNOWN( user_id == size_t(arg[1]) ); - CPPAD_ASSERT_UNKNOWN( user_n == size_t(arg[2]) ); - CPPAD_ASSERT_UNKNOWN( user_m == size_t(arg[3]) ); - - // call users function for this operation - user_atom->set_id(user_id); - CPPAD_ATOMIC_CALL( - user_k, user_tx, user_ty, user_px, user_py - ); -# ifndef NDEBUG - if( ! user_ok ) - { std::string msg = - atomic_base::class_name(user_index) - + ": atomic_base.reverse: returned false"; - CPPAD_ASSERT_KNOWN(false, msg.c_str() ); - } -# endif - for(j = 0; j < user_n; j++) if( user_ix[j] > 0 ) - { for(ell = 0; ell < user_k1; ell++) - Partial[user_ix[j] * K + ell] += - user_px[j * user_k1 + ell]; - } - user_state = user_end; - } - break; - - case UsrapOp: - // parameter argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( 0 < user_j && user_j <= user_n ); - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - --user_j; - user_ix[user_j] = 0; - user_tx[user_j * user_k1 + 0] = parameter[ arg[0]]; - for(ell = 1; ell < user_k1; ell++) - user_tx[user_j * user_k1 + ell] = Base(0.); - - if( user_j == 0 ) - user_state = user_start; - break; - - case UsravOp: - // variable argument in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_arg ); - CPPAD_ASSERT_UNKNOWN( 0 < user_j && user_j <= user_n ); - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) <= i_var ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - --user_j; - user_ix[user_j] = arg[0]; - for(ell = 0; ell < user_k1; ell++) - user_tx[user_j*user_k1 + ell] = Taylor[ arg[0] * J + ell]; - if( user_j == 0 ) - user_state = user_start; - break; - - case UsrrpOp: - // parameter result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( 0 < user_i && user_i <= user_m ); - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 1 ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - --user_i; - for(ell = 0; ell < user_k1; ell++) - { user_py[user_i * user_k1 + ell] = Base(0.); - user_ty[user_i * user_k1 + ell] = Base(0.); - } - user_ty[user_i * user_k1 + 0] = parameter[ arg[0] ]; - if( user_i == 0 ) - user_state = user_arg; - break; - - case UsrrvOp: - // variable result in an atomic operation sequence - CPPAD_ASSERT_UNKNOWN( user_state == user_ret ); - CPPAD_ASSERT_UNKNOWN( 0 < user_i && user_i <= user_m ); - --user_i; - for(ell = 0; ell < user_k1; ell++) - { user_py[user_i * user_k1 + ell] = - Partial[i_var * K + ell]; - user_ty[user_i * user_k1 + ell] = - Taylor[i_var * J + ell]; - } - if( user_i == 0 ) - user_state = user_arg; - break; - // ------------------------------------------------------------ - - case ZmulpvOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_par ); - reverse_zmulpv_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case ZmulvpOp: - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < num_par ); - reverse_zmulvp_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - case ZmulvvOp: - reverse_zmulvv_op( - d, i_var, arg, parameter, J, Taylor, K, Partial - ); - break; - // -------------------------------------------------- - - default: - CPPAD_ASSERT_UNKNOWN(false); - } - } -# if CPPAD_REVERSE_SWEEP_TRACE - std::cout << std::endl; -# endif - // values corresponding to BeginOp - CPPAD_ASSERT_UNKNOWN( i_op == 0 ); - CPPAD_ASSERT_UNKNOWN( i_var == 0 ); -} - -} // END_CPPAD_NAMESPACE - -// preprocessor symbols that are local to this file -# undef CPPAD_REVERSE_SWEEP_TRACE -# undef CPPAD_ATOMIC_CALL - -# endif diff --git a/ct_core/include/ct/external/cppad/local/set_get_in_parallel.hpp b/ct_core/include/ct/external/cppad/local/set_get_in_parallel.hpp deleted file mode 100644 index acd56e7ee..000000000 --- a/ct_core/include/ct/external/cppad/local/set_get_in_parallel.hpp +++ /dev/null @@ -1,67 +0,0 @@ -// $Id$ -# ifndef CPPAD_SET_GET_IN_PARALLEL_HPP -# define CPPAD_SET_GET_IN_PARALLEL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include -# include -namespace CppAD { // BEGIN_CPPAD_NAMESPACE - -/*! -\file set_get_in_parallel.hpp -File used to set and get user in_parallel routine. -*/ -/*! -Set and call the routine that determine if we are in parallel execution mode. - -\return -value retuned by most recent setting for in_parallel_new. -If set is true, -or the most recent setting is CPPAD_NULL (its initial value), -the return value is false. -Otherwise the function corresponding to the most recent setting -is called and its value returned by set_get_in_parallel. - -\param in_parallel_new [in] -If set is false, in_parallel_new it is not used. -Otherwise, the current value of in_parallel_new becomes the -most recent setting for in_parallel_user. - -\param set -If set is true, then parallel_new is becomes the most -recent setting for this set_get_in_parallel. -In this case, it is assumed that we are currently in sequential execution mode. -*/ -static bool set_get_in_parallel( - bool (*in_parallel_new)(void) , - bool set = false ) -{ static bool (*in_parallel_user)(void) = CPPAD_NULL; - - if( set ) - { in_parallel_user = in_parallel_new; - // Doing a raw assert in this case because set_get_in_parallel is used - // by ErrorHandler and hence cannot use ErrorHandler. - // CPPAD_ASSERT_UNKNOWN( in_parallel_user() == false ) - assert(in_parallel_user == CPPAD_NULL || in_parallel_user() == false); - return false; - } - // - if( in_parallel_user == CPPAD_NULL ) - return false; - // - return in_parallel_user(); -} - -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/sign.hpp b/ct_core/include/ct/external/cppad/local/sign.hpp deleted file mode 100644 index 97b826728..000000000 --- a/ct_core/include/ct/external/cppad/local/sign.hpp +++ /dev/null @@ -1,104 +0,0 @@ -// $Id: sign.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SIGN_HPP -# define CPPAD_SIGN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin sign$$ -$spell - CppAD - Dirac -$$ -$section The Sign: sign$$ - -$head Syntax$$ -$icode%y% = sign(%x%)%$$ - -$head Description$$ -Evaluates the $code sign$$ function which is defined by -$latex \[ -{\rm sign} (x) = -\left\{ \begin{array}{rl} - +1 & {\rm if} \; x > 0 \\ - 0 & {\rm if} \; x = 0 \\ - -1 & {\rm if} \; x < 0 -\end{array} \right. -\] $$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -CppAD computes the derivative of the $code sign$$ function as zero for all -argument values $icode x$$. -The correct mathematical derivative is different and -is given by -$latex \[ - {\rm sign}^{(1)} (x) = 2 \delta (x) -\] $$ -where $latex \delta (x)$$ is the Dirac Delta function. - -$head Example$$ -$children% - example/sign.cpp -%$$ -The file -$cref sign.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD AD::Sign (void) const -{ - AD result; - result.value_ = sign(value_); - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - if( Variable(*this) ) - { // add this operation to the tape - CPPAD_ASSERT_UNKNOWN( NumRes(SignOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(SignOp) == 1 ); - ADTape *tape = tape_this(); - - // corresponding operand address - tape->Rec_.PutArg(taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(SignOp); - // make result a variable - result.tape_id_ = tape->id_; - } - return result; -} - -template -inline AD sign(const AD &x) -{ return x.Sign(); } - -template -inline AD sign(const VecAD_reference &x) -{ return sign( x.ADBase() ); } - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/sign_op.hpp b/ct_core/include/ct/external/cppad/local/sign_op.hpp deleted file mode 100644 index bd48ca9ed..000000000 --- a/ct_core/include/ct/external/cppad/local/sign_op.hpp +++ /dev/null @@ -1,154 +0,0 @@ -// $Id: sign_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SIGN_OP_HPP -# define CPPAD_SIGN_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file sign_op.hpp -Forward and reverse mode calculations for z = sign(x). -*/ - -/*! -Compute forward mode Taylor coefficient for result of op = SignOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sign(x) -\endverbatim - -\copydetails forward_unary1_op -*/ -template -inline void forward_sign_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SignOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SignOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - - if( p == 0 ) - { z[0] = sign(x[0]); - p++; - } - for(size_t j = p; j <= q; j++) - z[j] = Base(0.); -} -/*! -Multiple direction forward mode Taylor coefficient for op = SignOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sign(x) -\endverbatim - -\copydetails forward_unary1_op_dir -*/ -template -inline void forward_sign_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SignOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SignOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - size_t m = (q - 1) * r + 1; - Base* z = taylor + i_z * num_taylor_per_var; - - for(size_t ell = 0; ell < r; ell++) - z[m+ell] = Base(0.); -} - -/*! -Compute zero order forward mode Taylor coefficient for result of op = SignOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sign(x) -\endverbatim - -\copydetails forward_unary1_op_0 -*/ -template -inline void forward_sign_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SignOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SignOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base x0 = *(taylor + i_x * cap_order); - Base* z = taylor + i_z * cap_order; - - z[0] = sign(x0); -} -/*! -Compute reverse mode partial derivatives for result of op = SignOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sign(x) -\endverbatim - -\copydetails reverse_unary1_op -*/ - -template -inline void reverse_sign_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SignOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SignOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // nothing to do because partials of sign are zero - return; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/sin_op.hpp b/ct_core/include/ct/external/cppad/local/sin_op.hpp deleted file mode 100644 index 525592fb1..000000000 --- a/ct_core/include/ct/external/cppad/local/sin_op.hpp +++ /dev/null @@ -1,241 +0,0 @@ -// $Id: sin_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SIN_OP_HPP -# define CPPAD_SIN_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file sin_op.hpp -Forward and reverse mode calculations for z = sin(x). -*/ - - -/*! -Compute forward mode Taylor coefficient for result of op = SinOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sin(x) -\endverbatim -The auxillary result is -\verbatim - y = cos(x) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op -*/ -template -inline void forward_sin_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SinOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SinOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* s = taylor + i_z * cap_order; - Base* c = s - cap_order; - - // rest of this routine is identical for the following cases: - // forward_sin_op, forward_cos_op, forward_sinh_op, forward_cosh_op. - // (except that there is a sign difference for the hyperbolic case). - size_t k; - if( p == 0 ) - { s[0] = sin( x[0] ); - c[0] = cos( x[0] ); - p++; - } - for(size_t j = p; j <= q; j++) - { - s[j] = Base(0); - c[j] = Base(0); - for(k = 1; k <= j; k++) - { s[j] += Base(k) * x[k] * c[j-k]; - c[j] -= Base(k) * x[k] * s[j-k]; - } - s[j] /= Base(j); - c[j] /= Base(j); - } -} -/*! -Compute forward mode Taylor coefficient for result of op = SinOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sin(x) -\endverbatim -The auxillary result is -\verbatim - y = cos(x) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op_dir -*/ -template -inline void forward_sin_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SinOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SinOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* s = taylor + i_z * num_taylor_per_var; - Base* c = s - num_taylor_per_var; - - - // rest of this routine is identical for the following cases: - // forward_sin_op, forward_cos_op, forward_sinh_op, forward_cosh_op - // (except that there is a sign difference for the hyperbolic case). - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - { s[m+ell] = Base(q) * x[m + ell] * c[0]; - c[m+ell] = - Base(q) * x[m + ell] * s[0]; - for(size_t k = 1; k < q; k++) - { s[m+ell] += Base(k) * x[(k-1)*r+1+ell] * c[(q-k-1)*r+1+ell]; - c[m+ell] -= Base(k) * x[(k-1)*r+1+ell] * s[(q-k-1)*r+1+ell]; - } - s[m+ell] /= Base(q); - c[m+ell] /= Base(q); - } -} - - -/*! -Compute zero order forward mode Taylor coefficient for result of op = SinOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sin(x) -\endverbatim -The auxillary result is -\verbatim - y = cos(x) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails forward_unary2_op_0 -*/ -template -inline void forward_sin_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SinOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SinOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* s = taylor + i_z * cap_order; // called z in documentation - Base* c = s - cap_order; // called y in documentation - - s[0] = sin( x[0] ); - c[0] = cos( x[0] ); -} - -/*! -Compute reverse mode partial derivatives for result of op = SinOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sin(x) -\endverbatim -The auxillary result is -\verbatim - y = cos(x) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails reverse_unary2_op -*/ - -template -inline void reverse_sin_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SinOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SinOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to first result - const Base* s = taylor + i_z * cap_order; // called z in doc - Base* ps = partial + i_z * nc_partial; - - // Taylor coefficients and partials corresponding to auxillary result - const Base* c = s - cap_order; // called y in documentation - Base* pc = ps - nc_partial; - - - // rest of this routine is identical for the following cases: - // reverse_sin_op, reverse_cos_op, reverse_sinh_op, reverse_cosh_op. - size_t j = d; - size_t k; - while(j) - { - ps[j] /= Base(j); - pc[j] /= Base(j); - for(k = 1; k <= j; k++) - { - px[k] += Base(k) * azmul(ps[j], c[j-k]); - px[k] -= Base(k) * azmul(pc[j], s[j-k]); - - ps[j-k] -= Base(k) * azmul(pc[j], x[k]); - pc[j-k] += Base(k) * azmul(ps[j], x[k]); - - } - --j; - } - px[0] += azmul(ps[0], c[0]); - px[0] -= azmul(pc[0], s[0]); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/sinh_op.hpp b/ct_core/include/ct/external/cppad/local/sinh_op.hpp deleted file mode 100644 index 50411d9df..000000000 --- a/ct_core/include/ct/external/cppad/local/sinh_op.hpp +++ /dev/null @@ -1,240 +0,0 @@ -// $Id: sinh_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SINH_OP_HPP -# define CPPAD_SINH_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file sinh_op.hpp -Forward and reverse mode calculations for z = sinh(x). -*/ - - -/*! -Compute forward mode Taylor coefficient for result of op = SinhOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sinh(x) -\endverbatim -The auxillary result is -\verbatim - y = cosh(x) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op -*/ -template -inline void forward_sinh_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SinhOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SinhOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* s = taylor + i_z * cap_order; - Base* c = s - cap_order; - - - // rest of this routine is identical for the following cases: - // forward_sin_op, forward_cos_op, forward_sinh_op, forward_cosh_op - // (except that there is a sign difference for hyperbolic case). - size_t k; - if( p == 0 ) - { s[0] = sinh( x[0] ); - c[0] = cosh( x[0] ); - p++; - } - for(size_t j = p; j <= q; j++) - { - s[j] = Base(0); - c[j] = Base(0); - for(k = 1; k <= j; k++) - { s[j] += Base(k) * x[k] * c[j-k]; - c[j] += Base(k) * x[k] * s[j-k]; - } - s[j] /= Base(j); - c[j] /= Base(j); - } -} -/*! -Compute forward mode Taylor coefficient for result of op = SinhOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sinh(x) -\endverbatim -The auxillary result is -\verbatim - y = cosh(x) -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op_dir -*/ -template -inline void forward_sinh_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SinhOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SinhOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* s = taylor + i_z * num_taylor_per_var; - Base* c = s - num_taylor_per_var; - - - // rest of this routine is identical for the following cases: - // forward_sin_op, forward_cos_op, forward_sinh_op, forward_cosh_op - // (except that there is a sign difference for the hyperbolic case). - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - { s[m+ell] = Base(q) * x[m + ell] * c[0]; - c[m+ell] = Base(q) * x[m + ell] * s[0]; - for(size_t k = 1; k < q; k++) - { s[m+ell] += Base(k) * x[(k-1)*r+1+ell] * c[(q-k-1)*r+1+ell]; - c[m+ell] += Base(k) * x[(k-1)*r+1+ell] * s[(q-k-1)*r+1+ell]; - } - s[m+ell] /= Base(q); - c[m+ell] /= Base(q); - } -} - -/*! -Compute zero order forward mode Taylor coefficient for result of op = SinhOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sinh(x) -\endverbatim -The auxillary result is -\verbatim - y = cosh(x) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails forward_unary2_op_0 -*/ -template -inline void forward_sinh_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SinhOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SinhOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* s = taylor + i_z * cap_order; // called z in documentation - Base* c = s - cap_order; // called y in documentation - - s[0] = sinh( x[0] ); - c[0] = cosh( x[0] ); -} -/*! -Compute reverse mode partial derivatives for result of op = SinhOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sinh(x) -\endverbatim -The auxillary result is -\verbatim - y = cosh(x) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails reverse_unary2_op -*/ - -template -inline void reverse_sinh_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SinhOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SinhOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to first result - const Base* s = taylor + i_z * cap_order; // called z in doc - Base* ps = partial + i_z * nc_partial; - - // Taylor coefficients and partials corresponding to auxillary result - const Base* c = s - cap_order; // called y in documentation - Base* pc = ps - nc_partial; - - - // rest of this routine is identical for the following cases: - // reverse_sin_op, reverse_cos_op, reverse_sinh_op, reverse_cosh_op. - size_t j = d; - size_t k; - while(j) - { - ps[j] /= Base(j); - pc[j] /= Base(j); - for(k = 1; k <= j; k++) - { - px[k] += Base(k) * azmul(ps[j], c[j-k]); - px[k] += Base(k) * azmul(pc[j], s[j-k]); - - ps[j-k] += Base(k) * azmul(pc[j], x[k]); - pc[j-k] += Base(k) * azmul(ps[j], x[k]); - - } - --j; - } - px[0] += azmul(ps[0], c[0]); - px[0] += azmul(pc[0], s[0]); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/sparse.hpp b/ct_core/include/ct/external/cppad/local/sparse.hpp deleted file mode 100644 index 1cc057000..000000000 --- a/ct_core/include/ct/external/cppad/local/sparse.hpp +++ /dev/null @@ -1,39 +0,0 @@ -// $Id: sparse.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SPARSE_HPP -# define CPPAD_SPARSE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Sparse$$ -$spell -$$ - - -$section Calculating Sparsity Patterns$$ - -$childtable% - cppad/local/for_sparse_jac.hpp% - cppad/local/rev_sparse_jac.hpp% - example/dependency.cpp% - cppad/local/rev_sparse_hes.hpp% - example/bool_sparsity.cpp -%$$ - -$end -*/ - -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/local/sparse_binary_op.hpp b/ct_core/include/ct/external/cppad/local/sparse_binary_op.hpp deleted file mode 100644 index 8ffb76f48..000000000 --- a/ct_core/include/ct/external/cppad/local/sparse_binary_op.hpp +++ /dev/null @@ -1,328 +0,0 @@ -// $Id: sparse_binary_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SPARSE_BINARY_OP_HPP -# define CPPAD_SPARSE_BINARY_OP_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file sparse_binary_op.hpp -Forward and reverse mode sparsity patterns for binary operators. -*/ - - -/*! -Forward mode Jacobian sparsity pattern for all binary operators. - -The C++ source code corresponding to a binary operation has the form -\verbatim - z = fun(x, y) -\endverbatim -where fun is a C++ binary function and both x and y are variables, -or it has the form -\verbatim - z = x op y -\endverbatim -where op is a C++ binary unary operator and both x and y are variables. - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param i_z -variable index corresponding to the result for this operation; -i.e., z. - -\param arg -\a arg[0] -variable index corresponding to the left operand for this operator; -i.e., x. -\n -\n arg[1] -variable index corresponding to the right operand for this operator; -i.e., y. - -\param sparsity -\b Input: -The set with index \a arg[0] in \a sparsity -is the sparsity bit pattern for x. -This identifies which of the independent variables the variable x -depends on. -\n -\n -\b Input: -The set with index \a arg[1] in \a sparsity -is the sparsity bit pattern for y. -This identifies which of the independent variables the variable y -depends on. -\n -\n -\b Output: -The set with index \a i_z in \a sparsity -is the sparsity bit pattern for z. -This identifies which of the independent variables the variable z -depends on. - -\par Checked Assertions: -\li \a arg[0] < \a i_z -\li \a arg[1] < \a i_z -*/ - -template -inline void forward_sparse_jacobian_binary_op( - size_t i_z , - const addr_t* arg , - Vector_set& sparsity ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < i_z ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < i_z ); - - sparsity.binary_union(i_z, arg[0], arg[1], sparsity); - - return; -} - -/*! -Reverse mode Jacobian sparsity pattern for all binary operators. - -The C++ source code corresponding to a unary operation has the form -\verbatim - z = fun(x, y) -\endverbatim -where fun is a C++ unary function and x and y are variables, -or it has the form -\verbatim - z = x op y -\endverbatim -where op is a C++ bianry operator and x and y are variables. - -This routine is given the sparsity patterns -for a function G(z, y, x, ... ) -and it uses them to compute the sparsity patterns for -\verbatim - H( y, x, w , u , ... ) = G[ z(x,y) , y , x , w , u , ... ] -\endverbatim - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param i_z -variable index corresponding to the result for this operation; -i.e., z. - -\param arg -\a arg[0] -variable index corresponding to the left operand for this operator; -i.e., x. - -\n -\n arg[1] -variable index corresponding to the right operand for this operator; -i.e., y. - -\param sparsity -The set with index \a i_z in \a sparsity -is the sparsity pattern for z corresponding ot the function G. -\n -\n -The set with index \a arg[0] in \a sparsity -is the sparsity pattern for x. -On input, it corresponds to the function G, -and on output it corresponds to H. -\n -\n -The set with index \a arg[1] in \a sparsity -is the sparsity pattern for y. -On input, it corresponds to the function G, -and on output it corresponds to H. -\n -\n - -\par Checked Assertions: -\li \a arg[0] < \a i_z -\li \a arg[1] < \a i_z -*/ -template -inline void reverse_sparse_jacobian_binary_op( - size_t i_z , - const addr_t* arg , - Vector_set& sparsity ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < i_z ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < i_z ); - - sparsity.binary_union(arg[0], arg[0], i_z, sparsity); - sparsity.binary_union(arg[1], arg[1], i_z, sparsity); - - return; -} - -/*! -Reverse mode Hessian sparsity pattern for add and subtract operators. - -The C++ source code corresponding to a unary operation has the form -\verbatim - z = x op y -\endverbatim -where op is + or - and x, y are variables. - -\copydetails reverse_sparse_hessian_binary_op -*/ -template -inline void reverse_sparse_hessian_addsub_op( - size_t i_z , - const addr_t* arg , - bool* jac_reverse , - Vector_set& for_jac_sparsity , - Vector_set& rev_hes_sparsity ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < i_z ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < i_z ); - - rev_hes_sparsity.binary_union(arg[0], arg[0], i_z, rev_hes_sparsity); - rev_hes_sparsity.binary_union(arg[1], arg[1], i_z, rev_hes_sparsity); - - jac_reverse[arg[0]] |= jac_reverse[i_z]; - jac_reverse[arg[1]] |= jac_reverse[i_z]; - - return; -} - -/*! -Reverse mode Hessian sparsity pattern for multiplication operator. - -The C++ source code corresponding to a unary operation has the form -\verbatim - z = x * y -\endverbatim -where x and y are variables. - -\copydetails reverse_sparse_hessian_binary_op -*/ -template -inline void reverse_sparse_hessian_mul_op( - size_t i_z , - const addr_t* arg , - bool* jac_reverse , - Vector_set& for_jac_sparsity , - Vector_set& rev_hes_sparsity ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < i_z ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < i_z ); - - rev_hes_sparsity.binary_union(arg[0], arg[0], i_z, rev_hes_sparsity); - rev_hes_sparsity.binary_union(arg[1], arg[1], i_z, rev_hes_sparsity); - - if( jac_reverse[i_z] ) - { rev_hes_sparsity.binary_union( - arg[0], arg[0], arg[1], for_jac_sparsity); - rev_hes_sparsity.binary_union( - arg[1], arg[1], arg[0], for_jac_sparsity); - } - - jac_reverse[arg[0]] |= jac_reverse[i_z]; - jac_reverse[arg[1]] |= jac_reverse[i_z]; - return; -} - -/*! -Reverse mode Hessian sparsity pattern for division operator. - -The C++ source code corresponding to a unary operation has the form -\verbatim - z = x / y -\endverbatim -where x and y are variables. - -\copydetails reverse_sparse_hessian_binary_op -*/ -template -inline void reverse_sparse_hessian_div_op( - size_t i_z , - const addr_t* arg , - bool* jac_reverse , - Vector_set& for_jac_sparsity , - Vector_set& rev_hes_sparsity ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < i_z ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < i_z ); - - rev_hes_sparsity.binary_union(arg[0], arg[0], i_z, rev_hes_sparsity); - rev_hes_sparsity.binary_union(arg[1], arg[1], i_z, rev_hes_sparsity); - - if( jac_reverse[i_z] ) - { rev_hes_sparsity.binary_union( - arg[0], arg[0], arg[1], for_jac_sparsity); - rev_hes_sparsity.binary_union( - arg[1], arg[1], arg[0], for_jac_sparsity); - rev_hes_sparsity.binary_union( - arg[1], arg[1], arg[1], for_jac_sparsity); - } - - jac_reverse[arg[0]] |= jac_reverse[i_z]; - jac_reverse[arg[1]] |= jac_reverse[i_z]; - return; -} - -/*! -Reverse mode Hessian sparsity pattern for power function. - -The C++ source code corresponding to a unary operation has the form -\verbatim - z = pow(x, y) -\endverbatim -where x and y are variables. - -\copydetails reverse_sparse_hessian_binary_op -*/ -template -inline void reverse_sparse_hessian_pow_op( - size_t i_z , - const addr_t* arg , - bool* jac_reverse , - Vector_set& for_jac_sparsity , - Vector_set& rev_hes_sparsity ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < i_z ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[1]) < i_z ); - - rev_hes_sparsity.binary_union(arg[0], arg[0], i_z, rev_hes_sparsity); - rev_hes_sparsity.binary_union(arg[1], arg[1], i_z, rev_hes_sparsity); - - if( jac_reverse[i_z] ) - { - rev_hes_sparsity.binary_union( - arg[0], arg[0], arg[0], for_jac_sparsity); - rev_hes_sparsity.binary_union( - arg[0], arg[0], arg[1], for_jac_sparsity); - - rev_hes_sparsity.binary_union( - arg[1], arg[1], arg[0], for_jac_sparsity); - rev_hes_sparsity.binary_union( - arg[1], arg[1], arg[1], for_jac_sparsity); - } - - // I cannot think of a case where this is necessary, but it including - // it makes it like the other cases. - jac_reverse[arg[0]] |= jac_reverse[i_z]; - jac_reverse[arg[1]] |= jac_reverse[i_z]; - return; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/sparse_hessian.hpp b/ct_core/include/ct/external/cppad/local/sparse_hessian.hpp deleted file mode 100644 index df153de89..000000000 --- a/ct_core/include/ct/external/cppad/local/sparse_hessian.hpp +++ /dev/null @@ -1,803 +0,0 @@ -// $Id: sparse_hessian.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SPARSE_HESSIAN_HPP -# define CPPAD_SPARSE_HESSIAN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin sparse_hessian$$ -$spell - jacobian - recomputed - CppAD - valarray - std - Bool - hes - const - Taylor - cppad - cmake - colpack -$$ - -$section Sparse Hessian: Easy Driver$$ -$mindex SparseHessian$$ - -$head Syntax$$ -$icode%hes% = %f%.SparseHessian(%x%, %w%) -%hes% = %f%.SparseHessian(%x%, %w%, %p%) -%n_sweep% = %f%.SparseHessian(%x%, %w%, %p%, %row%, %col%, %hes%, %work%) -%$$ - -$head Purpose$$ -We use $latex n$$ for the $cref/domain/seq_property/Domain/$$ size, -and $latex m$$ for the $cref/range/seq_property/Range/$$ size of $icode f$$. -We use $latex F : \B{R}^n \rightarrow \B{R}^m$$ do denote the -$cref/AD function/glossary/AD Function/$$ -corresponding to $icode f$$. -The syntax above sets $icode hes$$ to the Hessian -$latex \[ - H(x) = \dpow{2}{x} \sum_{i=1}^m w_i F_i (x) -\] $$ -This routine takes advantage of the sparsity of the Hessian -in order to reduce the amount of computation necessary. -If $icode row$$ and $icode col$$ are present, it also takes -advantage of the reduced set of elements of the Hessian that -need to be computed. -One can use speed tests (e.g. $cref speed_test$$) -to verify that results are computed faster -than when using the routine $cref Hessian$$. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/Uses Forward/sparse_hessian/Uses Forward/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %VectorBase%& %x% -%$$ -(see $cref/VectorBase/sparse_hessian/VectorBase/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the Hessian. - -$head w$$ -The argument $icode w$$ has prototype -$codei% - const %VectorBase%& %w% -%$$ -and size $latex m$$. -It specifies the value of $latex w_i$$ in the expression -for $icode hes$$. -The more components of $latex w$$ that are identically zero, -the more sparse the resulting Hessian may be (and hence the more efficient -the calculation of $icode hes$$ may be). - -$head p$$ -The argument $icode p$$ is optional and has prototype -$codei% - const %VectorSet%& %p% -%$$ -(see $cref/VectorSet/sparse_hessian/VectorSet/$$ below) -If it has elements of type $code bool$$, -its size is $latex n * n$$. -If it has elements of type $code std::set$$, -its size is $latex n$$ and all its set elements are between -zero and $latex n - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the Hessian $latex H(x)$$. -$pre - -$$ -If this sparsity pattern does not change between calls to -$codei SparseHessian$$, it should be faster to calculate $icode p$$ once and -pass this argument to $codei SparseHessian$$. -Furthermore, if you specify $icode work$$ in the calling sequence, -it is not necessary to keep the sparsity pattern; see the heading -$cref/p/sparse_hessian/work/p/$$ under the $icode work$$ description. -$pre - -$$ -In addition, -if you specify $icode p$$, CppAD will use the same -type of sparsity representation -(vectors of $code bool$$ or vectors of $code std::set$$) -for its internal calculations. -Otherwise, the representation -for the internal calculations is unspecified. - -$head row, col$$ -The arguments $icode row$$ and $icode col$$ are optional and have prototype -$codei% - const %VectorSize%& %row% - const %VectorSize%& %col% -%$$ -(see $cref/VectorSize/sparse_hessian/VectorSize/$$ below). -They specify which rows and columns of $latex H (x)$$ are -returned and in what order. -We use $latex K$$ to denote the value $icode%hes%.size()%$$ -which must also equal the size of $icode row$$ and $icode col$$. -Furthermore, -for $latex k = 0 , \ldots , K-1$$, it must hold that -$latex row[k] < n$$ and $latex col[k] < n$$. -In addition, -all of the $latex (row[k], col[k])$$ pairs must correspond to a true value -in the sparsity pattern $icode p$$. - -$head hes$$ -The result $icode hes$$ has prototype -$codei% - %VectorBase% %hes% -%$$ -In the case where $icode row$$ and $icode col$$ are not present, -the size of $icode hes$$ is $latex n * n$$ and -its size is $latex n * n$$. -In this case, for $latex i = 0 , \ldots , n - 1 $$ -and $latex ell = 0 , \ldots , n - 1$$ -$latex \[ - hes [ j * n + \ell ] = \DD{ w^{\rm T} F }{ x_j }{ x_\ell } ( x ) -\] $$ -$pre - -$$ -In the case where the arguments $icode row$$ and $icode col$$ are present, -we use $latex K$$ to denote the size of $icode hes$$. -The input value of its elements does not matter. -Upon return, for $latex k = 0 , \ldots , K - 1$$, -$latex \[ - hes [ k ] = \DD{ w^{\rm T} F }{ x_j }{ x_\ell } (x) - \; , \; - \; {\rm where} \; - j = row[k] - \; {\rm and } \; - \ell = col[k] -\] $$ - -$head work$$ -If this argument is present, it has prototype -$codei% - sparse_hessian_work& %work% -%$$ -This object can only be used with the routines $code SparseHessian$$. -During its the first use, information is stored in $icode work$$. -This is used to reduce the work done by future calls to $code SparseHessian$$ -with the same $icode f$$, $icode p$$, $icode row$$, and $icode col$$. -If a future call is made where any of these values have changed, -you must first call $icode%work%.clear()%$$ -to inform CppAD that this information needs to be recomputed. - -$subhead color_method$$ -The coloring algorithm determines which rows and columns -can be computed during the same sweep. -This field has prototype -$codei% - std::string %work%.color_method -%$$ -This value only matters on the first call to $code sparse_hessian$$ that -follows the $icode work$$ constructor or a call to -$icode%work%.clear()%$$. -$codei% - -"cppad.symmetric" -%$$ -This is the default coloring method (after a constructor or $code clear()$$). -It takes advantage of the fact that the Hessian matrix -is symmetric to find a coloring that requires fewer -$cref/sweeps/sparse_hessian/n_sweep/$$. -$codei% - -"cppad.general" -%$$ -This is the same as the $code "cppad"$$ method for the -$cref/sparse_jacobian/sparse_jacobian/work/color_method/$$ calculation. -$codei% - -"colpack.star" -%$$ -This method requires that -$cref colpack_prefix$$ was specified on the -$cref/cmake command/cmake/CMake Command/$$ line. -It also takes advantage of the fact that the Hessian matrix is symmetric. - -$subhead p$$ -If $icode work$$ is present, and it is not the first call after -its construction or a clear, -the sparsity pattern $icode p$$ is not used. -This enables one to free the sparsity pattern -and still compute corresponding sparse Hessians. - -$head n_sweep$$ -The return value $icode n_sweep$$ has prototype -$codei% - size_t %n_sweep% -%$$ -It is the number of first order forward sweeps -used to compute the requested Hessian values. -Each first forward sweep is followed by a second order reverse sweep -so it is also the number of reverse sweeps. -This is proportional to the total work that $code SparseHessian$$ does, -not counting the zero order forward sweep, -or the work to combine multiple columns into a single -forward-reverse sweep pair. - -$head VectorBase$$ -The type $icode VectorBase$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Base$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head VectorSet$$ -The type $icode VectorSet$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code bool$$ or $code std::set$$; -see $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for a discussion -of the difference. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$subhead Restrictions$$ -If $icode VectorSet$$ has elements of $code std::set$$, -then $icode%p%[%i%]%$$ must return a reference (not a copy) to the -corresponding set. -According to section 26.3.2.3 of the 1998 C++ standard, -$code std::valarray< std::set >$$ does not satisfy -this condition. - -$head VectorSize$$ -The type $icode VectorSize$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code size_t$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to any of the sparse Hessian routines, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0, %x%)%$$ -and the other coefficients are unspecified. - -$children% - example/sparse_hessian.cpp% - example/sub_sparse_hes.cpp% - example/sparse_sub_hes.cpp -%$$ - -$head Example$$ -The routine -$cref sparse_hessian.cpp$$ -is examples and tests of $code sparse_hessian$$. -It return $code true$$, if it succeeds and $code false$$ otherwise. - -$head Subset Hessian$$ -The routines -$cref sub_sparse_hes.cpp$$ and $cref sparse_sub_hes.cpp$$ -are examples and tests that compute a sparse Hessian -for a subset of the variables. -They return $code true$$, if they succeed and $code false$$ otherwise. - -$end ------------------------------------------------------------------------------ -*/ -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file sparse_hessian.hpp -Sparse Hessian driver routine and helper functions. -*/ -// =========================================================================== -/*! -class used by SparseHessian to hold information -so it does not need to be recomputed. -*/ -class sparse_hessian_work { - public: - /// Coloring method: "cppad", or "colpack" - /// (this field is set by user) - std::string color_method; - /// row and column indicies for return values - /// (some may be reflected by star coloring algorithm) - CppAD::vector row; - CppAD::vector col; - /// indices that sort the user row and col arrays by color - CppAD::vector order; - /// results of the coloring algorithm - CppAD::vector color; - - /// constructor - sparse_hessian_work(void) : color_method("cppad.symmetric") - { } - /// inform CppAD that this information needs to be recomputed - void clear(void) - { color_method = "cppad.symmetric"; - row.clear(); - col.clear(); - order.clear(); - color.clear(); - } -}; -// =========================================================================== -/*! -Private helper function that does computation for all Sparse Hessian cases. - -\tparam Base -is the base type for the recording that is stored in this ADFun. - -\tparam VectorSize -is \c sparse_pack, \c sparse_set or \c sparse_list. - -\param x [in] -is a vector specifing the point at which to compute the Hessian. - -\param w [in] -is the weighting vector that defines a scalar valued function by -a weighted sum of the components of the vector valued function -$latex F(x)$$. - -\param sparsity [in] -is the sparsity pattern for the Hessian that we are calculating. - -\param user_row [in] -is the vector of row indices for the returned Hessian values. - -\param user_col [in] -is the vector of columns indices for the returned Hessian values. -It must have the same size as user_row. - -\param hes [out] -is the vector of Hessian values. -It must have the same size as user_row. -The return value hes[k] is the second partial of -\f$ w^{\rm T} F(x)\f$ with respect to the -row[k] and col[k] component of \f$ x\f$. - -\param work -This structure contains information that is computed by \c SparseHessianCompute. -If the sparsity pattern, \c row vector, or \c col vectors -are not the same between calls to \c SparseHessianCompute, -\c work.clear() must be called to reinitialize \c work. - -\return -Is the number of first order forward sweeps used to compute the -requested Hessian values. -(This is also equal to the number of second order reverse sweeps.) -The total work, not counting the zero order -forward sweep, or the time to combine computations, is proportional to this -return value. -*/ -template -template -size_t ADFun::SparseHessianCompute( - const VectorBase& x , - const VectorBase& w , - VectorSet& sparsity , - const VectorSize& user_row , - const VectorSize& user_col , - VectorBase& hes , - sparse_hessian_work& work ) -{ - using CppAD::vectorBool; - size_t i, k, ell; - - CppAD::vector& row(work.row); - CppAD::vector& col(work.col); - CppAD::vector& color(work.color); - CppAD::vector& order(work.order); - - size_t n = Domain(); - - // some values - const Base zero(0); - const Base one(1); - - // check VectorBase is Simple Vector class with Base type elements - CheckSimpleVector(); - - // number of components of Hessian that are required - size_t K = hes.size(); - CPPAD_ASSERT_UNKNOWN( size_t( user_row.size() ) == K ); - CPPAD_ASSERT_UNKNOWN( size_t( user_col.size() ) == K ); - - CPPAD_ASSERT_UNKNOWN( size_t(x.size()) == n ); - CPPAD_ASSERT_UNKNOWN( color.size() == 0 || color.size() == n ); - CPPAD_ASSERT_UNKNOWN( row.size() == 0 || row.size() == K ); - CPPAD_ASSERT_UNKNOWN( col.size() == 0 || col.size() == K ); - - - // Point at which we are evaluating the Hessian - Forward(0, x); - - // check for case where nothing (except Forward above) to do - if( K == 0 ) - return 0; - - // Rows of the Hessian (i below) correspond to the forward mode index - // and columns (j below) correspond to the reverse mode index. - if( color.size() == 0 ) - { - CPPAD_ASSERT_UNKNOWN( sparsity.n_set() == n ); - CPPAD_ASSERT_UNKNOWN( sparsity.end() == n ); - - // copy user rwo and col to work space - row.resize(K); - col.resize(K); - for(k = 0; k < K; k++) - { row[k] = user_row[k]; - col[k] = user_col[k]; - } - - // execute coloring algorithm - color.resize(n); - if( work.color_method == "cppad.general" ) - color_general_cppad(sparsity, row, col, color); - else if( work.color_method == "cppad.symmetric" ) - color_symmetric_cppad(sparsity, row, col, color); - else if( work.color_method == "colpack.star" ) - { -# if CPPAD_HAS_COLPACK - color_symmetric_colpack(sparsity, row, col, color); -# else - CPPAD_ASSERT_KNOWN( - false, - "SparseHessian: work.color_method = colpack.star" - "and colpack_prefix missing from cmake command line." - ); -# endif - } - else - { CPPAD_ASSERT_KNOWN( - false, - "SparseHessian: work.color_method is not valid." - ); - } - - // put sorting indices in color order - VectorSize key(K); - order.resize(K); - for(k = 0; k < K; k++) - key[k] = color[ row[k] ]; - index_sort(key, order); - - } - size_t n_color = 1; - for(ell = 0; ell < n; ell++) if( color[ell] < n ) - n_color = std::max(n_color, color[ell] + 1); - - // direction vector for calls to forward (rows of the Hessian) - VectorBase u(n); - - // location for return values from reverse (columns of the Hessian) - VectorBase ddw(2 * n); - - // initialize the return value - for(k = 0; k < K; k++) - hes[k] = zero; - - // loop over colors - k = 0; - for(ell = 0; ell < n_color; ell++) - { CPPAD_ASSERT_UNKNOWN( color[ row[ order[k] ] ] == ell ); - - // combine all rows with this color - for(i = 0; i < n; i++) - { u[i] = zero; - if( color[i] == ell ) - u[i] = one; - } - // call forward mode for all these rows at once - Forward(1, u); - - // evaluate derivative of w^T * F'(x) * u - ddw = Reverse(2, w); - - // set the corresponding components of the result - while( k < K && color[ row[ order[k] ] ] == ell ) - { hes[ order[k] ] = ddw[ col[ order[k] ] * 2 + 1 ]; - k++; - } - } - return n_color; -} -// =========================================================================== -// Public Member Functions -// =========================================================================== -/*! -Compute user specified subset of a sparse Hessian. - -The C++ source code corresponding to this operation is -\verbatim - SparceHessian(x, w, p, row, col, hes, work) -\endverbatim - -\tparam Base -is the base type for the recording that is stored in this ADFun. - -\tparam VectorSize -is a simple vector class with elements of type \c size_t. - -\param x [in] -is a vector specifing the point at which to compute the Hessian. - -\param w [in] -is the weighting vector that defines a scalar valued function by -a weighted sum of the components of the vector valued function -$latex F(x)$$. - -\param p [in] -is the sparsity pattern for the Hessian that we are calculating. - -\param row [in] -is the vector of row indices for the returned Hessian values. - -\param col [in] -is the vector of columns indices for the returned Hessian values. -It must have the same size are r. - -\param hes [out] -is the vector of Hessian values. -It must have the same size are r. -The return value hes[k] is the second partial of -\f$ w^{\rm T} F(x)\f$ with respect to the -row[k] and col[k] component of \f$ x\f$. - -\param work -This structure contains information that is computed by \c SparseHessianCompute. -If the sparsity pattern, \c row vector, or \c col vectors -are not the same between calls to \c SparseHessian, -\c work.clear() must be called to reinitialize \c work. - -\return -Is the number of first order forward sweeps used to compute the -requested Hessian values. -(This is also equal to the number of second order reverse sweeps.) -The total work, not counting the zero order -forward sweep, or the time to combine computations, is proportional to this -return value. -*/ -template -template -size_t ADFun::SparseHessian( - const VectorBase& x , - const VectorBase& w , - const VectorSet& p , - const VectorSize& row , - const VectorSize& col , - VectorBase& hes , - sparse_hessian_work& work ) -{ - size_t n = Domain(); - size_t K = hes.size(); -# ifndef NDEBUG - size_t k; - CPPAD_ASSERT_KNOWN( - size_t(x.size()) == n , - "SparseHessian: size of x not equal domain dimension for f." - ); - - CPPAD_ASSERT_KNOWN( - size_t(row.size()) == K && size_t(col.size()) == K , - "SparseHessian: either r or c does not have the same size as ehs." - ); - CPPAD_ASSERT_KNOWN( - work.color.size() == 0 || work.color.size() == n, - "SparseHessian: invalid value in work." - ); - for(k = 0; k < K; k++) - { CPPAD_ASSERT_KNOWN( - row[k] < n, - "SparseHessian: invalid value in r." - ); - CPPAD_ASSERT_KNOWN( - col[k] < n, - "SparseHessian: invalid value in c." - ); - } - if( work.color.size() != 0 ) - for(size_t j = 0; j < n; j++) CPPAD_ASSERT_KNOWN( - work.color[j] <= n, - "SparseHessian: invalid value in work." - ); -# endif - // check for case where there is nothing to compute - size_t n_sweep = 0; - if( K == 0 ) - return n_sweep; - - typedef typename VectorSet::value_type Set_type; - typedef typename internal_sparsity::pattern_type Pattern_type; - Pattern_type s; - if( work.color.size() == 0 ) - { bool transpose = false; - sparsity_user2internal(s, p, n, n, transpose); - } - n_sweep = SparseHessianCompute(x, w, s, row, col, hes, work); - return n_sweep; -} -/*! -Compute a sparse Hessian. - -The C++ source code coresponding to this operation is -\verbatim - hes = SparseHessian(x, w, p) -\endverbatim - - -\tparam Base -is the base type for the recording that is stored in this -ADFun. - -\param x [in] -is a vector specifing the point at which to compute the Hessian. - -\param w [in] -The Hessian is computed for a weighted sum of the components -of the function corresponding to this ADFun object. -The argument \a w specifies the weights for each component. -It must have size equal to the range dimension for this ADFun object. - -\param p [in] -is a sparsity pattern for the Hessian. - -\return -Will be a vector of size \c n * n containing the Hessian of -at the point specified by \a x -(where \c n is the domain dimension for this ADFun object). -*/ -template -template -VectorBase ADFun::SparseHessian( - const VectorBase& x, const VectorBase& w, const VectorSet& p -) -{ size_t i, j, k; - - size_t n = Domain(); - VectorBase hes(n * n); - - CPPAD_ASSERT_KNOWN( - size_t(x.size()) == n, - "SparseHessian: size of x not equal domain size for f." - ); - - typedef typename VectorSet::value_type Set_type; - typedef typename internal_sparsity::pattern_type Pattern_type; - - // initialize the return value as zero - Base zero(0); - for(i = 0; i < n; i++) - for(j = 0; j < n; j++) - hes[i * n + j] = zero; - - // arguments to SparseHessianCompute - Pattern_type s; - CppAD::vector row; - CppAD::vector col; - sparse_hessian_work work; - bool transpose = false; - sparsity_user2internal(s, p, n, n, transpose); - k = 0; - for(i = 0; i < n; i++) - { s.begin(i); - j = s.next_element(); - while( j != s.end() ) - { row.push_back(i); - col.push_back(j); - k++; - j = s.next_element(); - } - } - size_t K = k; - VectorBase H(K); - - // now we have folded this into the following case - SparseHessianCompute(x, w, s, row, col, H, work); - - // now set the non-zero return values - for(k = 0; k < K; k++) - hes[ row[k] * n + col[k] ] = H[k]; - - return hes; -} -/*! -Compute a sparse Hessian - -The C++ source code coresponding to this operation is -\verbatim - hes = SparseHessian(x, w) -\endverbatim - - -\tparam Base -is the base type for the recording that is stored in this -ADFun object. -The argument \a w specifies the weights for each component. -It must have size equal to the range dimension for this ADFun object. - -\return -Will be a vector of size \c n * n containing the Hessian of -at the point specified by \a x -(where \c n is the domain dimension for this ADFun object). -*/ -template -template -VectorBase ADFun::SparseHessian(const VectorBase &x, const VectorBase &w) -{ size_t i, j, k; - typedef CppAD::vectorBool VectorBool; - - size_t m = Range(); - size_t n = Domain(); - - // determine the sparsity pattern p for Hessian of w^T F - VectorBool r(n * n); - for(j = 0; j < n; j++) - { for(k = 0; k < n; k++) - r[j * n + k] = false; - r[j * n + j] = true; - } - ForSparseJac(n, r); - // - VectorBool s(m); - for(i = 0; i < m; i++) - s[i] = w[i] != 0; - VectorBool p = RevSparseHes(n, s); - - // compute sparse Hessian - return SparseHessian(x, w, p); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/sparse_jacobian.hpp b/ct_core/include/ct/external/cppad/local/sparse_jacobian.hpp deleted file mode 100644 index 25b5b0cc5..000000000 --- a/ct_core/include/ct/external/cppad/local/sparse_jacobian.hpp +++ /dev/null @@ -1,1080 +0,0 @@ -// $Id: sparse_jacobian.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SPARSE_JACOBIAN_HPP -# define CPPAD_SPARSE_JACOBIAN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// maximum number of sparse directions to compute at the same time - -// # define CPPAD_SPARSE_JACOBIAN_MAX_MULTIPLE_DIRECTION 1 -# define CPPAD_SPARSE_JACOBIAN_MAX_MULTIPLE_DIRECTION 64 - -/* -$begin sparse_jacobian$$ -$spell - cppad - colpack - cmake - recomputed - valarray - std - CppAD - Bool - jac - Jacobian - Jacobians - const - Taylor -$$ - -$section Sparse Jacobian: Easy Driver$$ -$mindex SparseJacobian$$ - -$head Syntax$$ -$icode%jac% = %f%.SparseJacobian(%x%) -%jac% = %f%.SparseJacobian(%x%, %p%) -%n_sweep% = %f%.SparseJacobianForward(%x%, %p%, %row%, %col%, %jac%, %work%) -%n_sweep% = %f%.SparseJacobianReverse(%x%, %p%, %row%, %col%, %jac%, %work%) -%$$ - -$head Purpose$$ -We use $latex n$$ for the $cref/domain/seq_property/Domain/$$ size, -and $latex m$$ for the $cref/range/seq_property/Range/$$ size of $icode f$$. -We use $latex F : \B{R}^n \rightarrow \B{R}^m$$ do denote the -$cref/AD function/glossary/AD Function/$$ -corresponding to $icode f$$. -The syntax above sets $icode jac$$ to the Jacobian -$latex \[ - jac = F^{(1)} (x) -\] $$ -This routine takes advantage of the sparsity of the Jacobian -in order to reduce the amount of computation necessary. -If $icode row$$ and $icode col$$ are present, it also takes -advantage of the reduced set of elements of the Jacobian that -need to be computed. -One can use speed tests (e.g. $cref speed_test$$) -to verify that results are computed faster -than when using the routine $cref Jacobian$$. - -$head f$$ -The object $icode f$$ has prototype -$codei% - ADFun<%Base%> %f% -%$$ -Note that the $cref ADFun$$ object $icode f$$ is not $code const$$ -(see $cref/Uses Forward/sparse_jacobian/Uses Forward/$$ below). - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %VectorBase%& %x% -%$$ -(see $cref/VectorBase/sparse_jacobian/VectorBase/$$ below) -and its size -must be equal to $icode n$$, the dimension of the -$cref/domain/seq_property/Domain/$$ space for $icode f$$. -It specifies -that point at which to evaluate the Jacobian. - -$head p$$ -The argument $icode p$$ is optional and has prototype -$codei% - const %VectorSet%& %p% -%$$ -(see $cref/VectorSet/sparse_jacobian/VectorSet/$$ below). -If it has elements of type $code bool$$, -its size is $latex m * n$$. -If it has elements of type $code std::set$$, -its size is $latex m$$ and all its set elements are between -zero and $latex n - 1$$. -It specifies a -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ -for the Jacobian $latex F^{(1)} (x)$$. -$pre - -$$ -If this sparsity pattern does not change between calls to -$codei SparseJacobian$$, it should be faster to calculate $icode p$$ once -(using $cref ForSparseJac$$ or $cref RevSparseJac$$) -and then pass $icode p$$ to $codei SparseJacobian$$. -Furthermore, if you specify $icode work$$ in the calling sequence, -it is not necessary to keep the sparsity pattern; see the heading -$cref/p/sparse_jacobian/work/p/$$ under the $icode work$$ description. -$pre - -$$ -In addition, -if you specify $icode p$$, CppAD will use the same -type of sparsity representation -(vectors of $code bool$$ or vectors of $code std::set$$) -for its internal calculations. -Otherwise, the representation -for the internal calculations is unspecified. - -$head row, col$$ -The arguments $icode row$$ and $icode col$$ are optional and have prototype -$codei% - const %VectorSize%& %row% - const %VectorSize%& %col% -%$$ -(see $cref/VectorSize/sparse_jacobian/VectorSize/$$ below). -They specify which rows and columns of $latex F^{(1)} (x)$$ are -computes and in what order. -Not all the non-zero entries in $latex F^{(1)} (x)$$ need be computed, -but all the entries specified by $icode row$$ and $icode col$$ -must be possibly non-zero in the sparsity pattern. -We use $latex K$$ to denote the value $icode%jac%.size()%$$ -which must also equal the size of $icode row$$ and $icode col$$. -Furthermore, -for $latex k = 0 , \ldots , K-1$$, it must hold that -$latex row[k] < m$$ and $latex col[k] < n$$. - -$head jac$$ -The result $icode jac$$ has prototype -$codei% - %VectorBase%& %jac% -%$$ -In the case where the arguments $icode row$$ and $icode col$$ are not present, -the size of $icode jac$$ is $latex m * n$$ and -for $latex i = 0 , \ldots , m-1$$, -$latex j = 0 , \ldots , n-1$$, -$latex \[ - jac [ i * n + j ] = \D{ F_i }{ x_j } (x) -\] $$ -$pre - -$$ -In the case where the arguments $icode row$$ and $icode col$$ are present, -we use $latex K$$ to denote the size of $icode jac$$. -The input value of its elements does not matter. -Upon return, for $latex k = 0 , \ldots , K - 1$$, -$latex \[ - jac [ k ] = \D{ F_i }{ x_j } (x) - \; , \; - \; {\rm where} \; - i = row[k] - \; {\rm and } \; - j = col[k] -\] $$ - -$head work$$ -If this argument is present, it has prototype -$codei% - sparse_jacobian_work& %work% -%$$ -This object can only be used with the routines -$code SparseJacobianForward$$ and $code SparseJacobianReverse$$. -During its the first use, information is stored in $icode work$$. -This is used to reduce the work done by future calls to the same mode -(forward or reverse), -the same $icode f$$, $icode p$$, $icode row$$, and $icode col$$. -If a future call is for a different mode, -or any of these values have changed, -you must first call $icode%work%.clear()%$$ -to inform CppAD that this information needs to be recomputed. - -$subhead color_method$$ -The coloring algorithm determines which columns (forward mode) -or rows (reverse mode) can be computed during the same sweep. -This field has prototype -$codep% - std::string %work%.color_method -%$$ -and its default value (after a constructor or $code clear()$$) -is $code "cppad"$$. -If $cref colpack_prefix$$ is specified on the -$cref/cmake command/cmake/CMake Command/$$ line, -you can set this method to $code "colpack"$$. -This value only matters on the first call to $code sparse_jacobian$$ -that follows the $icode work$$ constructor or a call to -$icode%work%.clear()%$$. - -$subhead p$$ -If $icode work$$ is present, and it is not the first call after -its construction or a clear, -the sparsity pattern $icode p$$ is not used. -This enables one to free the sparsity pattern -and still compute corresponding sparse Jacobians. - -$head n_sweep$$ -The return value $icode n_sweep$$ has prototype -$codei% - size_t %n_sweep% -%$$ -If $code SparseJacobianForward$$ ($code SparseJacobianReverse$$) is used, -$icode n_sweep$$ is the number of first order forward (reverse) sweeps -used to compute the requested Jacobian values. -(This is also the number of colors determined by the coloring method -mentioned above). -This is proportional to the total work that $code SparseJacobian$$ does, -not counting the zero order forward sweep, -or the work to combine multiple columns (rows) into a single sweep. - -$head VectorBase$$ -The type $icode VectorBase$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Base$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head VectorSet$$ -The type $icode VectorSet$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code bool$$ or $code std::set$$; -see $cref/sparsity pattern/glossary/Sparsity Pattern/$$ for a discussion -of the difference. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$subhead Restrictions$$ -If $icode VectorSet$$ has elements of $code std::set$$, -then $icode%p%[%i%]%$$ must return a reference (not a copy) to the -corresponding set. -According to section 26.3.2.3 of the 1998 C++ standard, -$code std::valarray< std::set >$$ does not satisfy -this condition. - -$head VectorSize$$ -The type $icode VectorSize$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$code size_t$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Uses Forward$$ -After each call to $cref Forward$$, -the object $icode f$$ contains the corresponding -$cref/Taylor coefficients/glossary/Taylor Coefficient/$$. -After a call to any of the sparse Jacobian routines, -the zero order Taylor coefficients correspond to -$icode%f%.Forward(0, %x%)%$$ -and the other coefficients are unspecified. - -After $code SparseJacobian$$, -the previous calls to $cref Forward$$ are undefined. - -$head Example$$ -$children% - example/sparse_jacobian.cpp -%$$ -The routine -$cref sparse_jacobian.cpp$$ -is examples and tests of $code sparse_jacobian$$. -It return $code true$$, if it succeeds and $code false$$ otherwise. - -$end -============================================================================== -*/ -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file sparse_jacobian.hpp -Sparse Jacobian driver routine and helper functions. -*/ -// =========================================================================== -/*! -class used by SparseJacobian to hold information so it does not need to be -recomputed. -*/ -class sparse_jacobian_work { - public: - /// Coloring method: "cppad", or "colpack" - /// (this field is set by user) - std::string color_method; - /// indices that sort the user row and col arrays by color - CppAD::vector order; - /// results of the coloring algorithm - CppAD::vector color; - - /// constructor - sparse_jacobian_work(void) : color_method("cppad") - { } - /// reset coloring method to its default and - /// inform CppAD that color and order need to be recomputed - void clear(void) - { color_method = "cppad"; - order.clear(); - color.clear(); - } -}; -// =========================================================================== -/*! -Private helper function forward mode cases - -\tparam Base -is the base type for the recording that is stored in this -ADFun object. - -\tparam VectorBase -is a simple vector class with elements of type \a Base. - -\tparam VectorSet -is either \c sparse_pack, \c sparse_set or \c sparse_list. - -\tparam VectorSize -is a simple vector class with elements of type \c size_t. - -\param x [in] -is a vector specifing the point at which to compute the Jacobian. - -\param p_transpose [in] -If work.color.size() != 0, -then \c p_transpose is not used. -Otherwise, it is a -sparsity pattern for the transpose of the Jacobian of this ADFun object. -Note that we do not change the values in \c p_transpose, -but is not \c const because we use its iterator facility. - -\param row [in] -is the vector of row indices for the returned Jacobian values. - -\param col [in] -is the vector of columns indices for the returned Jacobian values. -It must have the same size as \c row. - -\param jac [out] -is the vector of Jacobian values. We use \c K to denote the size of \c jac. -The return value jac[k] is the partial of the -row[k] range component of the function with respect -the the col[k] domain component of its argument. - -\param work -work.color_method is an input. The rest of -this structure contains information that is computed by \c SparseJacobainFor. -If the sparsity pattern, \c row vector, or \c col vectors -are not the same between calls to \c SparseJacobianFor, -\c work.clear() must be called to reinitialize \c work. - -\return -Is the number of first order forward sweeps used to compute the -requested Jacobian values. The total work, not counting the zero order -forward sweep, or the time to combine computations, is proportional to this -return value. -*/ -template -template -size_t ADFun::SparseJacobianFor( - const VectorBase& x , - VectorSet& p_transpose , - const VectorSize& row , - const VectorSize& col , - VectorBase& jac , - sparse_jacobian_work& work ) -{ - size_t j, k, ell; - - CppAD::vector& order(work.order); - CppAD::vector& color(work.color); - - size_t m = Range(); - size_t n = Domain(); - - // some values - const Base zero(0); - const Base one(1); - - // check VectorBase is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_UNKNOWN( size_t(x.size()) == n ); - CPPAD_ASSERT_UNKNOWN( color.size() == 0 || color.size() == n ); - - // number of components of Jacobian that are required - size_t K = size_t(jac.size()); - CPPAD_ASSERT_UNKNOWN( size_t( row.size() ) == K ); - CPPAD_ASSERT_UNKNOWN( size_t( col.size() ) == K ); - - // Point at which we are evaluating the Jacobian - Forward(0, x); - - // check for case where nothing (except Forward above) to do - if( K == 0 ) - return 0; - - if( color.size() == 0 ) - { - CPPAD_ASSERT_UNKNOWN( p_transpose.n_set() == n ); - CPPAD_ASSERT_UNKNOWN( p_transpose.end() == m ); - - // execute coloring algorithm - color.resize(n); - if( work.color_method == "cppad" ) - color_general_cppad(p_transpose, col, row, color); - else if( work.color_method == "colpack" ) - { -# if CPPAD_HAS_COLPACK - color_general_colpack(p_transpose, col, row, color); -# else - CPPAD_ASSERT_KNOWN( - false, - "SparseJacobianForward: work.color_method = colpack " - "and colpack_prefix missing from cmake command line." - ); -# endif - } - else CPPAD_ASSERT_KNOWN( - false, - "SparseJacobianForward: work.color_method is not valid." - ); - - // put sorting indices in color order - VectorSize key(K); - order.resize(K); - for(k = 0; k < K; k++) - key[k] = color[ col[k] ]; - index_sort(key, order); - } - size_t n_color = 1; - for(j = 0; j < n; j++) if( color[j] < n ) - n_color = std::max(n_color, color[j] + 1); - - // initialize the return value - for(k = 0; k < K; k++) - jac[k] = zero; - -# if CPPAD_SPARSE_JACOBIAN_MAX_MULTIPLE_DIRECTION == 1 - // direction vector and return values for calls to forward - VectorBase dx(n), dy(m); - - // loop over colors - k = 0; - for(ell = 0; ell < n_color; ell++) - { CPPAD_ASSERT_UNKNOWN( color[ col[ order[k] ] ] == ell ); - - // combine all columns with this color - for(j = 0; j < n; j++) - { dx[j] = zero; - if( color[j] == ell ) - dx[j] = one; - } - // call forward mode for all these columns at once - dy = Forward(1, dx); - - // set the corresponding components of the result - while( k < K && color[ col[order[k]] ] == ell ) - { jac[ order[k] ] = dy[row[order[k]]]; - k++; - } - } -# else - // abbreviation for this value - size_t max_r = CPPAD_SPARSE_JACOBIAN_MAX_MULTIPLE_DIRECTION; - CPPAD_ASSERT_UNKNOWN( max_r > 1 ); - - // count the number of colors done so far - size_t count_color = 0; - // count the sparse matrix entries done so far - k = 0; - while( count_color < n_color ) - { // number of colors we will do this time - size_t r = std::min(max_r , n_color - count_color); - VectorBase dx(n * r), dy(m * r); - - // loop over colors we will do this tme - for(ell = 0; ell < r; ell++) - { // combine all columns with this color - for(j = 0; j < n; j++) - { dx[j * r + ell] = zero; - if( color[j] == ell + count_color ) - dx[j * r + ell] = one; - } - } - size_t q = 1; - dy = Forward(q, r, dx); - - // store results - for(ell = 0; ell < r; ell++) - { // set the components of the result for this color - while( k < K && color[ col[order[k]] ] == ell + count_color ) - { jac[ order[k] ] = dy[ row[order[k]] * r + ell ]; - k++; - } - } - count_color += r; - } -# endif - return n_color; -} -/*! -Private helper function for reverse mode cases. - -\tparam Base -is the base type for the recording that is stored in this -ADFun object. - -\tparam VectorBase -is a simple vector class with elements of type \a Base. - -\tparam VectorSet -is either \c sparse_pack, \c sparse_set or \c sparse_list. - -\tparam VectorSize -is a simple vector class with elements of type \c size_t. - -\param x [in] -is a vector specifing the point at which to compute the Jacobian. - -\param p [in] -If work.color.size() != 0, then \c p is not used. -Otherwise, it is a -sparsity pattern for the Jacobian of this ADFun object. -Note that we do not change the values in \c p, -but is not \c const because we use its iterator facility. - -\param row [in] -is the vector of row indices for the returned Jacobian values. - -\param col [in] -is the vector of columns indices for the returned Jacobian values. -It must have the same size as \c row. - -\param jac [out] -is the vector of Jacobian values. -It must have the same size as \c row. -The return value jac[k] is the partial of the -row[k] range component of the function with respect -the the col[k] domain component of its argument. - -\param work -work.color_method is an input. The rest of -This structure contains information that is computed by \c SparseJacobainRev. -If the sparsity pattern, \c row vector, or \c col vectors -are not the same between calls to \c SparseJacobianRev, -\c work.clear() must be called to reinitialize \c work. - -\return -Is the number of first order reverse sweeps used to compute the -reverse Jacobian values. The total work, not counting the zero order -forward sweep, or the time to combine computations, is proportional to this -return value. -*/ -template -template -size_t ADFun::SparseJacobianRev( - const VectorBase& x , - VectorSet& p , - const VectorSize& row , - const VectorSize& col , - VectorBase& jac , - sparse_jacobian_work& work ) -{ - size_t i, k, ell; - - CppAD::vector& order(work.order); - CppAD::vector& color(work.color); - - size_t m = Range(); - size_t n = Domain(); - - // some values - const Base zero(0); - const Base one(1); - - // check VectorBase is Simple Vector class with Base type elements - CheckSimpleVector(); - - CPPAD_ASSERT_UNKNOWN( size_t(x.size()) == n ); - CPPAD_ASSERT_UNKNOWN (color.size() == m || color.size() == 0 ); - - // number of components of Jacobian that are required - size_t K = size_t(jac.size()); - CPPAD_ASSERT_UNKNOWN( size_t( size_t( row.size() ) ) == K ); - CPPAD_ASSERT_UNKNOWN( size_t( size_t( col.size() ) ) == K ); - - // Point at which we are evaluating the Jacobian - Forward(0, x); - - // check for case where nothing (except Forward above) to do - if( K == 0 ) - return 0; - - if( color.size() == 0 ) - { - CPPAD_ASSERT_UNKNOWN( p.n_set() == m ); - CPPAD_ASSERT_UNKNOWN( p.end() == n ); - - // execute the coloring algorithm - color.resize(m); - if( work.color_method == "cppad" ) - color_general_cppad(p, row, col, color); - else if( work.color_method == "colpack" ) - { -# if CPPAD_HAS_COLPACK - color_general_colpack(p, row, col, color); -# else - CPPAD_ASSERT_KNOWN( - false, - "SparseJacobianReverse: work.color_method = colpack " - "and colpack_prefix missing from cmake command line." - ); -# endif - } - else CPPAD_ASSERT_KNOWN( - false, - "SparseJacobianReverse: work.color_method is not valid." - ); - - // put sorting indices in color order - VectorSize key(K); - order.resize(K); - for(k = 0; k < K; k++) - key[k] = color[ row[k] ]; - index_sort(key, order); - } - size_t n_color = 1; - for(i = 0; i < m; i++) if( color[i] < m ) - n_color = std::max(n_color, color[i] + 1); - - // weighting vector for calls to reverse - VectorBase w(m); - - // location for return values from Reverse - VectorBase dw(n); - - // initialize the return value - for(k = 0; k < K; k++) - jac[k] = zero; - - // loop over colors - k = 0; - for(ell = 0; ell < n_color; ell++) - { CPPAD_ASSERT_UNKNOWN( color[ row[ order[k] ] ] == ell ); - - // combine all the rows with this color - for(i = 0; i < m; i++) - { w[i] = zero; - if( color[i] == ell ) - w[i] = one; - } - // call reverse mode for all these rows at once - dw = Reverse(1, w); - - // set the corresponding components of the result - while( k < K && color[ row[order[k]] ] == ell ) - { jac[ order[k] ] = dw[col[order[k]]]; - k++; - } - } - return n_color; -} -// ========================================================================== -// Public Member functions -// ========================================================================== -/*! -Compute user specified subset of a sparse Jacobian using forward mode. - -The C++ source code corresponding to this operation is -\verbatim - SparceJacobianForward(x, p, row, col, jac, work) -\endverbatim - -\tparam Base -is the base type for the recording that is stored in this -ADFun object. - -\tparam VectorBase -is a simple vector class with elements of type \a Base. - -\tparam VectorSet -is a simple vector class with elements of type -\c bool or \c std::set. - -\tparam VectorSize -is a simple vector class with elements of type \c size_t. - -\param x [in] -is a vector specifing the point at which to compute the Jacobian. - -\param p [in] -is the sparsity pattern for the Jacobian that we are calculating. - -\param row [in] -is the vector of row indices for the returned Jacobian values. - -\param col [in] -is the vector of columns indices for the returned Jacobian values. -It must have the same size as \c row. - -\param jac [out] -is the vector of Jacobian values. -It must have the same size as \c row. -The return value jac[k] is the partial of the -row[k] range component of the function with respect -the the col[k] domain component of its argument. - -\param work [in,out] -this structure contains information that depends on the function object, -sparsity pattern, \c row vector, and \c col vector. -If they are not the same between calls to \c SparseJacobianForward, -\c work.clear() must be called to reinitialize them. - -\return -Is the number of first order forward sweeps used to compute the -requested Jacobian values. The total work, not counting the zero order -forward sweep, or the time to combine computations, is proportional to this -return value. -*/ -template -template -size_t ADFun::SparseJacobianForward( - const VectorBase& x , - const VectorSet& p , - const VectorSize& row , - const VectorSize& col , - VectorBase& jac , - sparse_jacobian_work& work ) -{ - size_t n = Domain(); - size_t m = Range(); - size_t K = jac.size(); -# ifndef NDEBUG - size_t k; - CPPAD_ASSERT_KNOWN( - size_t(x.size()) == n , - "SparseJacobianForward: size of x not equal domain dimension for f." - ); - CPPAD_ASSERT_KNOWN( - size_t(row.size()) == K && size_t(col.size()) == K , - "SparseJacobianForward: either r or c does not have " - "the same size as jac." - ); - CPPAD_ASSERT_KNOWN( - work.color.size() == 0 || work.color.size() == n, - "SparseJacobianForward: invalid value in work." - ); - for(k = 0; k < K; k++) - { CPPAD_ASSERT_KNOWN( - row[k] < m, - "SparseJacobianForward: invalid value in r." - ); - CPPAD_ASSERT_KNOWN( - col[k] < n, - "SparseJacobianForward: invalid value in c." - ); - } - if( work.color.size() != 0 ) - for(size_t j = 0; j < n; j++) CPPAD_ASSERT_KNOWN( - work.color[j] <= n, - "SparseJacobianForward: invalid value in work." - ); -# endif - // check for case where there is nothing to compute - size_t n_sweep = 0; - if( K == 0 ) - return n_sweep; - - typedef typename VectorSet::value_type Set_type; - typedef typename internal_sparsity::pattern_type Pattern_type; - Pattern_type s_transpose; - if( work.color.size() == 0 ) - { bool transpose = true; - sparsity_user2internal(s_transpose, p, m, n, transpose); - } - n_sweep = SparseJacobianFor(x, s_transpose, row, col, jac, work); - return n_sweep; -} -/*! -Compute user specified subset of a sparse Jacobian using forward mode. - -The C++ source code corresponding to this operation is -\verbatim - SparceJacobianReverse(x, p, row, col, jac, work) -\endverbatim - -\tparam Base -is the base type for the recording that is stored in this -ADFun object. - -\tparam VectorBase -is a simple vector class with elements of type \a Base. - -\tparam VectorSet -is a simple vector class with elements of type -\c bool or \c std::set. - -\tparam VectorSize -is a simple vector class with elements of type \c size_t. - -\param x [in] -is a vector specifing the point at which to compute the Jacobian. - -\param p [in] -is the sparsity pattern for the Jacobian that we are calculating. - -\param row [in] -is the vector of row indices for the returned Jacobian values. - -\param col [in] -is the vector of columns indices for the returned Jacobian values. -It must have the same size as \c row. - -\param jac [out] -is the vector of Jacobian values. -It must have the same size as \c row. -The return value jac[k] is the partial of the -row[k] range component of the function with respect -the the col[k] domain component of its argument. - -\param work [in,out] -this structure contains information that depends on the function object, -sparsity pattern, \c row vector, and \c col vector. -If they are not the same between calls to \c SparseJacobianReverse, -\c work.clear() must be called to reinitialize them. - -\return -Is the number of first order reverse sweeps used to compute the -reverse Jacobian values. The total work, not counting the zero order -forward sweep, or the time to combine computations, is proportional to this -return value. -*/ -template -template -size_t ADFun::SparseJacobianReverse( - const VectorBase& x , - const VectorSet& p , - const VectorSize& row , - const VectorSize& col , - VectorBase& jac , - sparse_jacobian_work& work ) -{ - size_t m = Range(); - size_t n = Domain(); - size_t K = jac.size(); -# ifndef NDEBUG - size_t k; - CPPAD_ASSERT_KNOWN( - size_t(x.size()) == n , - "SparseJacobianReverse: size of x not equal domain dimension for f." - ); - CPPAD_ASSERT_KNOWN( - size_t(row.size()) == K && size_t(col.size()) == K , - "SparseJacobianReverse: either r or c does not have " - "the same size as jac." - ); - CPPAD_ASSERT_KNOWN( - work.color.size() == 0 || work.color.size() == m, - "SparseJacobianReverse: invalid value in work." - ); - for(k = 0; k < K; k++) - { CPPAD_ASSERT_KNOWN( - row[k] < m, - "SparseJacobianReverse: invalid value in r." - ); - CPPAD_ASSERT_KNOWN( - col[k] < n, - "SparseJacobianReverse: invalid value in c." - ); - } - if( work.color.size() != 0 ) - for(size_t i = 0; i < m; i++) CPPAD_ASSERT_KNOWN( - work.color[i] <= m, - "SparseJacobianReverse: invalid value in work." - ); -# endif - // check for case where there is nothing to compute - size_t n_sweep = 0; - if( K == 0 ) - return n_sweep; - - typedef typename VectorSet::value_type Set_type; - typedef typename internal_sparsity::pattern_type Pattern_type; - Pattern_type s; - if( work.color.size() == 0 ) - { bool transpose = false; - sparsity_user2internal(s, p, m, n, transpose); - } - n_sweep = SparseJacobianRev(x, s, row, col, jac, work); - return n_sweep; -} -/*! -Compute a sparse Jacobian. - -The C++ source code corresponding to this operation is -\verbatim - jac = SparseJacobian(x, p) -\endverbatim - -\tparam Base -is the base type for the recording that is stored in this -ADFun object. - -\tparam VectorBase -is a simple vector class with elements of type \a Base. - -\tparam VectorSet -is a simple vector class with elements of type -\c bool or \c std::set. - -\param x [in] -is a vector specifing the point at which to compute the Jacobian. - -\param p [in] -is the sparsity pattern for the Jacobian that we are calculating. - -\return -Will be a vector if size \c m * n containing the Jacobian at the -specified point (in row major order). -*/ -template -template -VectorBase ADFun::SparseJacobian( - const VectorBase& x, const VectorSet& p -) -{ size_t i, j, k; - - size_t m = Range(); - size_t n = Domain(); - VectorBase jac(m * n); - - CPPAD_ASSERT_KNOWN( - size_t(x.size()) == n, - "SparseJacobian: size of x not equal domain size for f." - ); - CheckSimpleVector(); - - typedef typename VectorSet::value_type Set_type; - typedef typename internal_sparsity::pattern_type Pattern_type; - - // initialize the return value as zero - Base zero(0); - for(i = 0; i < m; i++) - for(j = 0; j < n; j++) - jac[i * n + j] = zero; - - sparse_jacobian_work work; - CppAD::vector row; - CppAD::vector col; - if( n <= m ) - { - // need an internal copy of sparsity pattern - Pattern_type s_transpose; - bool transpose = true; - sparsity_user2internal(s_transpose, p, m, n, transpose); - - k = 0; - for(j = 0; j < n; j++) - { s_transpose.begin(j); - i = s_transpose.next_element(); - while( i != s_transpose.end() ) - { row.push_back(i); - col.push_back(j); - k++; - i = s_transpose.next_element(); - } - } - size_t K = k; - VectorBase J(K); - - // now we have folded this into the following case - SparseJacobianFor(x, s_transpose, row, col, J, work); - - // now set the non-zero return values - for(k = 0; k < K; k++) - jac[ row[k] * n + col[k] ] = J[k]; - } - else - { - // need an internal copy of sparsity pattern - Pattern_type s; - bool transpose = false; - sparsity_user2internal(s, p, m, n, transpose); - - k = 0; - for(i = 0; i < m; i++) - { s.begin(i); - j = s.next_element(); - while( j != s.end() ) - { row.push_back(i); - col.push_back(j); - k++; - j = s.next_element(); - } - } - size_t K = k; - VectorBase J(K); - - // now we have folded this into the following case - SparseJacobianRev(x, s, row, col, J, work); - - // now set the non-zero return values - for(k = 0; k < K; k++) - jac[ row[k] * n + col[k] ] = J[k]; - } - - return jac; -} - -/*! -Compute a sparse Jacobian. - -The C++ source code corresponding to this operation is -\verbatim - jac = SparseJacobian(x) -\endverbatim - -\tparam Base -is the base type for the recording that is stored in this -ADFun object. - -\tparam VectorBase -is a simple vector class with elements of the \a Base. - -\param x [in] -is a vector specifing the point at which to compute the Jacobian. - -\return -Will be a vector of size \c m * n containing the Jacobian at the -specified point (in row major order). -*/ -template -template -VectorBase ADFun::SparseJacobian( const VectorBase& x ) -{ typedef CppAD::vectorBool VectorBool; - - size_t m = Range(); - size_t n = Domain(); - - // sparsity pattern for Jacobian - VectorBool p(m * n); - - if( n <= m ) - { size_t j, k; - - // use forward mode - VectorBool r(n * n); - for(j = 0; j < n; j++) - { for(k = 0; k < n; k++) - r[j * n + k] = false; - r[j * n + j] = true; - } - p = ForSparseJac(n, r); - } - else - { size_t i, k; - - // use reverse mode - VectorBool s(m * m); - for(i = 0; i < m; i++) - { for(k = 0; k < m; k++) - s[i * m + k] = false; - s[i * m + i] = true; - } - p = RevSparseJac(m, s); - } - return SparseJacobian(x, p); -} - -} // END_CPPAD_NAMESPACE -# undef CPPAD_SPARSE_JACOBIAN_MAX_MULTIPLE_DIRECTION -# endif diff --git a/ct_core/include/ct/external/cppad/local/sparse_list.hpp b/ct_core/include/ct/external/cppad/local/sparse_list.hpp deleted file mode 100644 index f7c8752cd..000000000 --- a/ct_core/include/ct/external/cppad/local/sparse_list.hpp +++ /dev/null @@ -1,553 +0,0 @@ -// $Id: sparse_list.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SPARSE_LIST_HPP -# define CPPAD_SPARSE_LIST_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file sparse_list.hpp -Vector of sets of positive integers stored as singly linked lists. -*/ - -/*! -Vector of sets of positive integers, each set stored as a singly -linked list. -*/ -class sparse_list { -public: - /// type used for each set in the vector of sets - /// (note that next is index in data_ for next element in this set). - struct pair_size_t { size_t value; size_t next; }; -private: - // ----------------------------------------------------------------- - /// Number of sets that we are representing - /// (set by constructor and resize). - size_t n_set_; - - /// Possible elements in each set are 0, 1, ..., end_ - 1; - size_t end_; - - /// The data for all the elements in all the sets - CppAD::pod_vector data_; - - /// next element - pair_size_t next_pair_; - - /// number of elements in data_ that are no longer being used. - size_t data_not_used_; - - /// temporary data vector used for garbage collection - CppAD::pod_vector data_tmp_; - // ----------------------------------------------------------------- - /*! Private member function that counts number of elements in a set. - - \param index - is the index of the set we are counting. - - \par Checked Assertions - \li index < n_set_ - */ - size_t number_elements(size_t index) const - { CPPAD_ASSERT_UNKNOWN(index < n_set_ ); - - size_t count = 0; - size_t i = index; - size_t value = data_[i].value; - while( value < end_ ) - { count++; - i = data_[i].next; - value = data_[i].value; - } - return count; - } - // ----------------------------------------------------------------- - /// Private member functions that does garbage collection. - void collect_garbage(void) - { CPPAD_ASSERT_UNKNOWN( 2 * data_not_used_ > data_.size() ); - // - CPPAD_ASSERT_UNKNOWN( - number_elements() + n_set_ + data_not_used_ == data_.size() - ); - - // copy the sets to a temporary data vector - data_tmp_.erase(); - data_tmp_.extend(n_set_); - for(size_t i = 0; i < n_set_; i++) - { size_t next = i; - size_t next_tmp = i; - // - size_t value = data_[next].value; - while( value < end_ ) - { data_tmp_[next_tmp].value = value; - // data_tmp_[next_tmp].next = data_tmp_.extend(1); - // does not seem to work ? - size_t index_tmp = data_tmp_.extend(1); - data_tmp_[next_tmp].next = index_tmp; - // - next = data_[next].next; - next_tmp = data_tmp_[next_tmp].next; - // - value = data_[next].value; - } - data_tmp_[next_tmp].value = end_; - } - CPPAD_ASSERT_UNKNOWN( - data_tmp_.size() + data_not_used_ == data_.size() - ); - - // swap the tmp and old data vectors - data_.swap(data_tmp_); - - // all of the elements are used in this new version of data_ - data_not_used_ = 0; - } -public: - // ----------------------------------------------------------------- - /*! Default constructor (no sets) - */ - sparse_list(void) : - n_set_(0) , - end_(0) , - data_not_used_(0) - { next_pair_.value = end_; } - // ----------------------------------------------------------------- - /*! Using copy constructor is a programing (not user) error - - \param v - vector that we are attempting to make a copy of. - */ - sparse_list(const sparse_list& v) - { // Error: - // Probably a sparse_list argument has been passed by value - CPPAD_ASSERT_UNKNOWN(false); - } - // ----------------------------------------------------------------- - /*! Destructor - */ - ~sparse_list(void) - { } - // ----------------------------------------------------------------- - /*! Change number of sets, end marker, and initialize all sets as empty - - If \c n_set_in is zero, any memory currently allocated for this object - is freed. Otherwise, new memory may be allocated for the sets (if needed). - - \param n_set_in - is the number of sets in this vector of sets. - - \param end_in - is the maximum element plus one (the minimum element is 0). - */ - void resize(size_t n_set_in, size_t end_in) - { n_set_ = n_set_in; - end_ = end_in; - next_pair_.value = end_in; - data_not_used_ = 0; - if( n_set_in == 0 ) - { // free all memory connected with this object - data_.free(); - return; - } - // now start a new vector with empty sets - data_.erase(); - data_.extend(n_set_); - for(size_t i = 0; i < n_set_; i++) - data_[i].value = end_; - } - // ----------------------------------------------------------------- - /*! Add one element to a set. - - \param index - is the index for this set in the vector of sets. - - \param element - is the element we are adding to the set. - - \par Checked Assertions - \li index < n_set_ - \li element < end_ - */ - void add_element(size_t index, size_t element) - { CPPAD_ASSERT_UNKNOWN( index < n_set_ ); - CPPAD_ASSERT_UNKNOWN( element < end_ ); - - size_t value = data_[index].value; - - // case of inserting at beginning - if( element < value ) - { size_t insert = data_.extend(1); - data_[insert] = data_[index]; - data_[index].value = element; - data_[index].next = insert; - return; - } - - // search list for place to insert - size_t previous = index; - size_t current = data_[previous].next; - value = data_[current].value; - while( value < element ) - { previous = current; - current = data_[previous].next; - value = data_[current].value; - } - if( element != value ) - { CPPAD_ASSERT_UNKNOWN( element < value ); - size_t insert = data_.extend(1); - // - data_[insert].next = data_[previous].next; - data_[previous].next = insert; - data_[insert].value = element; - } - } - // ----------------------------------------------------------------- - /*! Is an element in a set. - - \param index - is the index for this set in the vector of sets. - - \param element - is the element we are checking to see if it is in set. - - \par Checked Assertions - \li index < n_set_ - \li element < end_ - */ - bool is_element(size_t index, size_t element) - { CPPAD_ASSERT_UNKNOWN( index < n_set_ ); - CPPAD_ASSERT_UNKNOWN( element < end_ ); - - size_t i = index; - size_t value = data_[i].value; - while( value < element ) - { i = data_[i].next; - value = data_[i].value; - } - - return element == value; - } - // ----------------------------------------------------------------- - /*! Begin retrieving elements from one of the sets. - - \param index - is the index for the set that is going to be retrieved. - The elements of the set are retrieved in increasing order. - - \par Checked Assertions - \li index < n_set_ - - */ - void begin(size_t index) - { // initialize element to search for in this set - CPPAD_ASSERT_UNKNOWN( index < n_set_ ); - next_pair_ = data_[index]; - - return; - } - // ----------------------------------------------------------------- - /*! Get the next element from the current retrieval set. - - \return - is the next element in the set with index - specified by the previous call to \c begin. - If no such element exists, \c this->end() is returned. - - \par Assumption - There is no call to \c add_element or \c binary_union - since the previvious \c begin - */ - size_t next_element(void) - { size_t element = next_pair_.value; - if( element != end_ ) - next_pair_ = data_[next_pair_.next]; - - return element; - } - // ----------------------------------------------------------------- - /*! Assign the empty set to one of the sets. - - \param target - is the index of the set we are setting to the empty set. - - \par data_not_used_ - increments this value by number of elements lost. - - \par Checked Assertions - \li target < n_set_ - */ - void clear(size_t target) - { CPPAD_ASSERT_UNKNOWN( target < n_set_ ); - - // number of elements that will be deleted by this operation - size_t number_delete = number_elements(target); - - // delete the elements from the set - data_[target].value = end_; - - // adjust data_not_used_ - data_not_used_ += number_delete; - - if( 2 * data_not_used_ > data_.size() ) - collect_garbage(); - } - // ----------------------------------------------------------------- - /*! Assign one set equal to another set. - - \param this_target - is the index (in this \c sparse_list object) of the set being assinged. - - \param other_source - is the index (in the other \c sparse_list object) of the - that we are using as the value to assign to the target set. - - \param other - is the other \c sparse_list object (which may be the same as this - \c sparse_list object). - - \par data_not_used_ - increments this value by number of elements lost. - - \par Checked Assertions - \li this_target < n_set_ - \li other_index < other.n_set_ - */ - void assignment( - size_t this_target , - size_t other_source , - const sparse_list& other ) - { CPPAD_ASSERT_UNKNOWN( this_target < n_set_ ); - CPPAD_ASSERT_UNKNOWN( other_source < other.n_set_ ); - CPPAD_ASSERT_UNKNOWN( end_ == other.end() ); - - // check if we are assigning a set to itself - if( (this == &other) & (this_target == other_source) ) - return; - - // number of elements that will be deleted by this operation - size_t number_delete = number_elements(this_target); - - size_t this_index = this_target; - size_t other_index = other_source; - size_t value = other.data_[other_index].value; - while( value != end_ ) - { size_t next = data_.extend(1); - data_[this_index].value = value; - data_[this_index].next = next; - this_index = next; - other_index = other.data_[other_index].next; - value = other.data_[other_index].value; - } - data_[this_index].value = end_; - - // adjust data_not_used_ - data_not_used_ += number_delete; - - if( 2 * data_not_used_ > data_.size() ) - collect_garbage(); - } - // ----------------------------------------------------------------- - /*! Assign a set equal to the union of two other sets. - - \param this_target - is the index (in this \c sparse_list object) of the set being assinged. - - \param this_left - is the index (in this \c sparse_list object) of the - left operand for the union operation. - It is OK for \a this_target and \a this_left to be the same value. - - \param other_right - is the index (in the other \c sparse_list object) of the - right operand for the union operation. - It is OK for \a this_target and \a other_right to be the same value. - - \param other - is the other \c sparse_list object (which may be the same as this - \c sparse_list object). - - \par Checked Assertions - \li this_target < n_set_ - \li this_left < n_set_ - \li other_right < other.n_set_ - */ - void binary_union( - size_t this_target , - size_t this_left , - size_t other_right , - const sparse_list& other ) - { - CPPAD_ASSERT_UNKNOWN( this_target < n_set_ ); - CPPAD_ASSERT_UNKNOWN( this_left < n_set_ ); - CPPAD_ASSERT_UNKNOWN( other_right < other.n_set_ ); - CPPAD_ASSERT_UNKNOWN( end_ == other.end() ); - - // determine if we will delete the original version of the target - size_t number_delete = 0; - bool delete_target = this_target == this_left; - delete_target |= (this == &other) & (this_target == other_right); - if( delete_target ) - { // number of elements that will be deleted by this operation - number_delete = number_elements(this_target); - } - - // value and next for left and right sets - size_t left_value = data_[this_left].value; - size_t left_next = data_[this_left].next; - size_t right_value = other.data_[other_right].value; - size_t right_next = other.data_[other_right].next; - - // merge left and right sets to form new target set - size_t current = this_target; - while( (left_value < end_) | (right_value < end_) ) - { if( left_value == right_value ) - { right_value = other.data_[right_next].value; - right_next = other.data_[right_next].next; - } - size_t next = data_.extend(1); - data_[current].next = next; - if( left_value < right_value ) - { data_[current].value = left_value; - left_value = data_[left_next].value; - left_next = data_[left_next].next; - } - else - { data_[current].value = right_value; - right_value = other.data_[right_next].value; - right_next = other.data_[right_next].next; - } - current = next; - } - data_[current].value = end_; - - // adjust data_not_used_ - data_not_used_ += number_delete; - - if( 2 * data_not_used_ > data_.size() ) - collect_garbage(); - } - // ----------------------------------------------------------------- - /*! Sum over all sets of the number of elements - - /return - The the total number of elements - */ - size_t number_elements(void) const - { size_t i, count; - count = 0; - for(i = 0; i < n_set_; i++) - count += number_elements(i); - return count; - } - // ----------------------------------------------------------------- - /*! Fetch n_set for vector of sets object. - - \return - Number of from sets for this vector of sets object - */ - size_t n_set(void) const - { return n_set_; } - // ----------------------------------------------------------------- - /*! Fetch end for this vector of sets object. - - \return - is the maximum element value plus one (the minimum element value is 0). - */ - size_t end(void) const - { return end_; } -}; -// Tell pod_vector class that each pair_size_t is plain old data and hence -// the corresponding constructor need not be called. -template <> inline bool is_pod(void) -{ return true; } - -/*! -Copy a user vector of sets sparsity pattern to an internal sparse_list object. - -\tparam VectorSet -is a simple vector with elements of type \c std::list. - -\param internal -The input value of sparisty does not matter. -Upon return it contains the same sparsity pattern as \c user -(or the transposed sparsity pattern). - -\param user -sparsity pattern that we are placing \c internal. - -\param n_row -number of rows in the sparsity pattern in \c user -(range dimension). - -\param n_col -number of columns in the sparsity pattern in \c user -(domain dimension). - -\param transpose -if true, the sparsity pattern in \c internal is the transpose -of the one in \c user. -Otherwise it is the same sparsity pattern. -*/ -template -void sparsity_user2internal( - sparse_list& internal , - const VectorSet& user , - size_t n_row , - size_t n_col , - bool transpose ) -{ - CPPAD_ASSERT_KNOWN( - size_t( user.size() ) == n_row, - "Size of this vector of sets sparsity pattern is not equal\n" - "the range dimension for the corresponding function." - ); - - size_t i, j; - std::set::const_iterator itr; - - // transposed pattern case - if( transpose ) - { internal.resize(n_col, n_row); - for(i = 0; i < n_row; i++) - { itr = user[i].begin(); - while(itr != user[i].end()) - { j = *itr++; - CPPAD_ASSERT_KNOWN( - j < n_col, - "An element in this vector of sets sparsity pattern " - "is greater than or equal\n" - "the domain dimension for the corresponding function." - ); - internal.add_element(j, i); - } - } - return; - } - - // same pattern case - internal.resize(n_row, n_col); - for(i = 0; i < n_row; i++) - { itr = user[i].begin(); - while(itr != user[i].end()) - { j = *itr++; - CPPAD_ASSERT_UNKNOWN( j < n_col ); - internal.add_element(i, j); - } - } - return; -} - - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/sparse_pack.hpp b/ct_core/include/ct/external/cppad/local/sparse_pack.hpp deleted file mode 100644 index b5ffb0f58..000000000 --- a/ct_core/include/ct/external/cppad/local/sparse_pack.hpp +++ /dev/null @@ -1,416 +0,0 @@ -// $Id: sparse_pack.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SPARSE_PACK_HPP -# define CPPAD_SPARSE_PACK_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file sparse_pack.hpp -Vector of sets of positive integers stored as a packed array of bools. -*/ - -/*! -Vector of sets of postivie integers, each set stored as a packed boolean array. -*/ - -class sparse_pack { -private: - /// Type used to pack elements (should be the same as corresponding - /// typedef in multiple_n_bit() in test_more/sparse_hacobian.cpp) - typedef size_t Pack; - /// Number of bits per Pack value - static const size_t n_bit_ = std::numeric_limits::digits; - /// Number of sets that we are representing - /// (set by constructor and resize). - size_t n_set_; - /// Possible elements in each set are 0, 1, ..., end_ - 1 - /// (set by constructor and resize). - size_t end_; - /// Number of \c Pack values necessary to represent \c end_ bits. - /// (set by constructor and resize). - size_t n_pack_; - /// Data for all the sets. - pod_vector data_; - /// index for which we were retrieving next_element - /// (use n_set_ if no such index exists). - size_t next_index_; - /// Next element to start search at - /// (use end_ for no such element exists; i.e., past end of the set). - size_t next_element_; -public: - // ----------------------------------------------------------------- - /*! Default constructor (no sets) - */ - sparse_pack(void) : - n_set_(0) , - end_(0) , - n_pack_(0) , - next_index_(0) , - next_element_(0) - { } - // ----------------------------------------------------------------- - /*! Make use of copy constructor an error - - \param v - vector that we are attempting to make a copy of. - */ - sparse_pack(const sparse_pack& v) - { // Error: - // Probably a sparse_pack argument has been passed by value - CPPAD_ASSERT_UNKNOWN(0); - } - // ----------------------------------------------------------------- - /*! Destructor - */ - ~sparse_pack(void) - { } - // ----------------------------------------------------------------- - /*! Change number of sets, set end, and initialize all sets as empty - - If \c n_set_in is zero, any memory currently allocated for this object - is freed. Otherwise, new memory may be allocated for the sets (if needed). - - \param n_set_in - is the number of sets in this vector of sets. - - \param end_in - is the maximum element plus one (the minimum element is 0). - */ - void resize(size_t n_set_in, size_t end_in) - { - n_set_ = n_set_in; - end_ = end_in; - if( n_set_ == 0 ) - { data_.free(); - return; - } - // now start a new vector with empty sets - Pack zero(0); - data_.erase(); - - n_pack_ = ( 1 + (end_ - 1) / n_bit_ ); - size_t i = n_set_ * n_pack_; - - if( i > 0 ) - { data_.extend(i); - while(i--) - data_[i] = zero; - } - - // values that signify past end of list - next_index_ = n_set_; - next_element_ = end_; - } - // ----------------------------------------------------------------- - /*! Add one element to a set. - - \param index - is the index for this set in the vector of sets. - - \param element - is the element we are adding to the set. - - \par Checked Assertions - \li index < n_set_ - \li element < end_ - */ - void add_element(size_t index, size_t element) - { static Pack one(1); - CPPAD_ASSERT_UNKNOWN( index < n_set_ ); - CPPAD_ASSERT_UNKNOWN( element < end_ ); - size_t j = element / n_bit_; - size_t k = element - j * n_bit_; - Pack mask = one << k; - data_[ index * n_pack_ + j] |= mask; - } - // ----------------------------------------------------------------- - /*! Is an element of a set. - - \param index - is the index for this set in the vector of sets. - - \param element - is the element we are checking to see if it is in the set. - - \par Checked Assertions - \li index < n_set_ - \li element < end_ - */ - bool is_element(size_t index, size_t element) - { static Pack one(1); - static Pack zero(0); - CPPAD_ASSERT_UNKNOWN( index < n_set_ ); - CPPAD_ASSERT_UNKNOWN( element < end_ ); - size_t j = element / n_bit_; - size_t k = element - j * n_bit_; - Pack mask = one << k; - return (data_[ index * n_pack_ + j] & mask) != zero; - } - // ----------------------------------------------------------------- - /*! Begin retrieving elements from one of the sets. - - \param index - is the index for the set that is going to be retrieved. - The elements of the set are retrieved in increasing order. - - \par Checked Assertions - \li index < n_set_ - */ - void begin(size_t index) - { // initialize element to search for in this set - CPPAD_ASSERT_UNKNOWN( index < n_set_ ); - next_index_ = index; - next_element_ = 0; - } - /*! Get the next element from the current retrieval set. - - \return - is the next element in the set with index - specified by the previous call to \c begin. - If no such element exists, \c this->end() is returned. - */ - size_t next_element(void) - { static Pack one(1); - CPPAD_ASSERT_UNKNOWN( next_index_ < n_set_ ); - CPPAD_ASSERT_UNKNOWN( next_element_ <= end_ ); - - if( next_element_ == end_ ) - return end_; - - // initialize packed data index - size_t j = next_element_ / n_bit_; - - // initialize bit index - size_t k = next_element_ - j * n_bit_; - - // start search at this packed value - Pack check = data_[ next_index_ * n_pack_ + j ]; - while( true ) - { // increment next element before checking this one - next_element_++; - // check if this element is in the set - if( check & (one << k) ) - return next_element_ - 1; - // check if no more elements in the set - if( next_element_ == end_ ) - return end_; - // increment bit index in Pack value so corresponds to - // next element - k++; - CPPAD_ASSERT_UNKNOWN( k <= n_bit_ ); - if( k == n_bit_ ) - { // get next packed value - k = 0; - j++; - CPPAD_ASSERT_UNKNOWN( j < n_pack_ ); - check = data_[ next_index_ * n_pack_ + j ]; - } - } - // should never get here - CPPAD_ASSERT_UNKNOWN(false); - return end_; - } - // ----------------------------------------------------------------- - /*! Assign the empty set to one of the sets. - - \param target - is the index of the set we are setting to the empty set. - - \par Checked Assertions - \li target < n_set_ - */ - void clear(size_t target) - { // value with all its bits set to false - static Pack zero(0); - CPPAD_ASSERT_UNKNOWN( target < n_set_ ); - size_t t = target * n_pack_; - - size_t j = n_pack_; - while(j--) - data_[t++] = zero; - } - // ----------------------------------------------------------------- - /*! Assign one set equal to another set. - - \param this_target - is the index (in this \c sparse_pack object) of the set being assinged. - - \param other_value - is the index (in the other \c sparse_pack object) of the - that we are using as the value to assign to the target set. - - \param other - is the other \c sparse_pack object (which may be the same as this - \c sparse_pack object). - - \par Checked Assertions - \li this_target < n_set_ - \li other_value < other.n_set_ - \li n_pack_ == other.n_pack_ - */ - void assignment( - size_t this_target , - size_t other_value , - const sparse_pack& other ) - { CPPAD_ASSERT_UNKNOWN( this_target < n_set_ ); - CPPAD_ASSERT_UNKNOWN( other_value < other.n_set_ ); - CPPAD_ASSERT_UNKNOWN( n_pack_ == other.n_pack_ ); - size_t t = this_target * n_pack_; - size_t v = other_value * n_pack_; - - size_t j = n_pack_; - while(j--) - data_[t++] = other.data_[v++]; - } - - // ----------------------------------------------------------------- - /*! Assing a set equal to the union of two other sets. - - \param this_target - is the index (in this \c sparse_pack object) of the set being assinged. - - \param this_left - is the index (in this \c sparse_pack object) of the - left operand for the union operation. - It is OK for \a this_target and \a this_left to be the same value. - - \param other_right - is the index (in the other \c sparse_pack object) of the - right operand for the union operation. - It is OK for \a this_target and \a other_right to be the same value. - - \param other - is the other \c sparse_pack object (which may be the same as this - \c sparse_pack object). - - \par Checked Assertions - \li this_target < n_set_ - \li this_left < n_set_ - \li other_right < other.n_set_ - \li n_pack_ == other.n_pack_ - */ - void binary_union( - size_t this_target , - size_t this_left , - size_t other_right , - const sparse_pack& other ) - { CPPAD_ASSERT_UNKNOWN( this_target < n_set_ ); - CPPAD_ASSERT_UNKNOWN( this_left < n_set_ ); - CPPAD_ASSERT_UNKNOWN( other_right < other.n_set_ ); - CPPAD_ASSERT_UNKNOWN( n_pack_ == other.n_pack_ ); - - size_t t = this_target * n_pack_; - size_t l = this_left * n_pack_; - size_t r = other_right * n_pack_; - - size_t j = n_pack_; - while(j--) - data_[t++] = ( data_[l++] | other.data_[r++] ); - } - // ----------------------------------------------------------------- - /*! Amount of memory used by this vector of sets - - \return - The amount of memory in units of type unsigned char memory. - */ - size_t memory(void) const - { return n_set_ * n_pack_ * sizeof(Pack); - } - // ----------------------------------------------------------------- - /*! Fetch n_set for vector of sets object. - - \return - Number of from sets for this vector of sets object - */ - size_t n_set(void) const - { return n_set_; } - // ----------------------------------------------------------------- - /*! Fetch end for this vector of sets object. - - \return - is the maximum element value plus one (the minimum element value is 0). - */ - size_t end(void) const - { return end_; } -}; - -/*! -Copy a user vector of bools sparsity pattern to an internal sparse_pack object. - -\tparam VectorBool -is a simple vector with elements of type bool. - -\param internal -The input value of sparisty does not matter. -Upon return it contains the same sparsity pattern as \c user -(or the transposed sparsity pattern). - -\param user -sparsity pattern that we are placing \c internal. - -\param n_row -number of rows in the sparsity pattern in \c user -(rand dimension). - -\param n_col -number of columns in the sparsity pattern in \c user -(domain dimension). - -\param transpose -if true, the sparsity pattern in \c internal is the transpose -of the one in \c user. -Otherwise it is the same sparsity pattern. -*/ -template -void sparsity_user2internal( - sparse_pack& internal , - const VectorBool& user , - size_t n_row , - size_t n_col , - bool transpose ) -{ - size_t i, j; - - CPPAD_ASSERT_KNOWN( - size_t( user.size() ) == n_row * n_col, - "Size of this vector of bools sparsity pattern is not equal\n" - "product of domain and range dimensions for corresponding function." - ); - - // transposed pattern case - if( transpose ) - { internal.resize(n_col, n_row); - for(j = 0; j < n_col; j++) - { for(i = 0; i < n_row; i++) - { if( user[ i * n_col + j ] ) - internal.add_element(j, i); - } - } - return; - } - - // same pattern case - internal.resize(n_row, n_col); - for(i = 0; i < n_row; i++) - { for(j = 0; j < n_col; j++) - { if( user[ i * n_col + j ] ) - internal.add_element(i, j); - } - } - return; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/sparse_pattern.hpp b/ct_core/include/ct/external/cppad/local/sparse_pattern.hpp deleted file mode 100644 index c1dd39e62..000000000 --- a/ct_core/include/ct/external/cppad/local/sparse_pattern.hpp +++ /dev/null @@ -1,59 +0,0 @@ -// $Id: sparse_pattern.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SPARSE_PATTERN_HPP -# define CPPAD_SPARSE_PATTERN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// necessary definitions -# include -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file sparse_pattern.hpp -Determine internal spasity pattern from correpsonding element type. -*/ - -/*! -Template structure used obtain the internal sparsity pattern type -form the corresponding element type. -The general form is not valid, must use a specialization. - -\tparam Element_type -type of an element in the sparsity structrue. - -\par internal_sparsity::pattern_type -is the type of the corresponding internal sparsity pattern. -*/ -template struct internal_sparsity; -/*! -Specilization for \c bool elements. -*/ -template <> -struct internal_sparsity -{ - typedef sparse_pack pattern_type; -}; -/*! -Specilization for std::set elements. -*/ -template <> -struct internal_sparsity< std::set > -{ - typedef CPPAD_INTERNAL_SPARSE_SET pattern_type; -}; - -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/local/sparse_set.hpp b/ct_core/include/ct/external/cppad/local/sparse_set.hpp deleted file mode 100644 index e9328b7de..000000000 --- a/ct_core/include/ct/external/cppad/local/sparse_set.hpp +++ /dev/null @@ -1,377 +0,0 @@ -// $Id: sparse_set.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SPARSE_SET_HPP -# define CPPAD_SPARSE_SET_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include -# include -# include - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file sparse_set.hpp -Vector of sets of positive integers stored as std::set. -*/ - -/*! -Vector of sets of positive integers, each set stored as a standard set. -*/ - -class sparse_set { -private: - /// type used for each set in the vector sets - typedef std::set Set; - /// Number of sets that we are representing - /// (set by constructor and resize). - size_t n_set_; - /// Possible elements in each set are 0, 1, ..., end_ - 1 - /// (set by constructor and resize). - size_t end_; - /// The vector of sets - CppAD::vector data_; - /// index for which we were retrieving next_element - /// (use n_set_ if no such index exists). - size_t next_index_; - /// Next element that we will return using next_element - /// (use end_ for no such element exists; i.e., past end of the set). - Set::iterator next_element_; -public: - // ----------------------------------------------------------------- - /*! Default constructor (no sets) - */ - sparse_set(void) : - n_set_(0) , - end_(0) , - next_index_(0) - { } - // ----------------------------------------------------------------- - /*! Make use of copy constructor an error - - \param v - vector that we are attempting to make a copy of. - */ - sparse_set(const sparse_set& v) - { // Error: - // Probably a sparse_set argument has been passed by value - CPPAD_ASSERT_UNKNOWN(false); - } - // ----------------------------------------------------------------- - /*! Destructor - */ - ~sparse_set(void) - { } - // ----------------------------------------------------------------- - /*! Change number of sets, set end, and initialize all sets as empty - - - If \c n_set_in is zero, any memory currently allocated for this object - is freed. Otherwise, new memory may be allocated for the sets (if needed). - - \param n_set_in - is the number of sets in this vector of sets. - - \param end_in - is the maximum element plus one (the minimum element is 0). - */ - void resize(size_t n_set_in, size_t end_in) - { n_set_ = n_set_in; - end_ = end_in; - if( n_set_ == 0 ) - { // free all memory connected with data_ - data_.clear(); - return; - } - // now start a new vector with empty sets - data_.resize(n_set_); - - // value that signfies past end of list - next_index_ = n_set_; - } - // ----------------------------------------------------------------- - /*! Add one element to a set. - - \param index - is the index for this set in the vector of sets. - - \param element - is the element we are adding to the set. - - \par Checked Assertions - \li index < n_set_ - \li element < end_ - */ - void add_element(size_t index, size_t element) - { // This routine should use the std::insert operator - // that cashes the iterator of previous insertion for when - // insertions occur in order. We should speed test that this - // actually makes things faster. - CPPAD_ASSERT_UNKNOWN( index < n_set_ ); - CPPAD_ASSERT_UNKNOWN( element < end_ ); - data_[ index ].insert( element ); - } - // ----------------------------------------------------------------- - /*! Is an element of a set. - - \param index - is the index for this set in the vector of sets. - - \param element - is the element we are adding to the set. - - \par Checked Assertions - \li index < n_set_ - \li element < end_ - */ - bool is_element(size_t index, size_t element) - { // This routine should use the std::insert operator - // that cashes the iterator of previous insertion for when - // insertions occur in order. We should speed test that this - // actually makes things faster. - CPPAD_ASSERT_UNKNOWN( index < n_set_ ); - CPPAD_ASSERT_UNKNOWN( element < end_ ); - std::set::iterator itr = data_[ index ].find( element ); - return itr != data_[index].end(); - } - // ----------------------------------------------------------------- - /*! Begin retrieving elements from one of the sets. - - \param index - is the index for the set that is going to be retrieved. - The elements of the set are retrieved in increasing order. - - \par Checked Assertions - \li index < n_set_ - */ - void begin(size_t index) - { // initialize element to search for in this set - CPPAD_ASSERT_UNKNOWN( index < n_set_ ); - next_index_ = index; - next_element_ = data_[index].begin(); - - return; - } - // ----------------------------------------------------------------- - /*! Get the next element from the current retrieval set. - - \return - is the next element in the set with index - specified by the previous call to \c begin. - If no such element exists, \c this->end() is returned. - */ - size_t next_element(void) - { - if( next_element_ == data_[next_index_].end() ) - return end_; - - return *next_element_++; - } - // ----------------------------------------------------------------- - /*! Assign the empty set to one of the sets. - - \param target - is the index of the set we are setting to the empty set. - - \par Checked Assertions - \li target < n_set_ - */ - void clear(size_t target) - { CPPAD_ASSERT_UNKNOWN( target < n_set_ ); - data_[target].clear(); - } - // ----------------------------------------------------------------- - /*! Assign one set equal to another set. - - \param this_target - is the index (in this \c sparse_set object) of the set being assinged. - - \param other_value - is the index (in the other \c sparse_set object) of the - that we are using as the value to assign to the target set. - - \param other - is the other \c sparse_set object (which may be the same as this - \c sparse_set object). - - \par Checked Assertions - \li this_target < n_set_ - \li other_value < other.n_set_ - */ - void assignment( - size_t this_target , - size_t other_value , - const sparse_set& other ) - { CPPAD_ASSERT_UNKNOWN( this_target < n_set_ ); - CPPAD_ASSERT_UNKNOWN( other_value < other.n_set_ ); - - data_[this_target] = other.data_[other_value]; - } - - // ----------------------------------------------------------------- - /*! Assign a set equal to the union of two other sets. - - \param this_target - is the index (in this \c sparse_set object) of the set being assinged. - - \param this_left - is the index (in this \c sparse_set object) of the - left operand for the union operation. - It is OK for \a this_target and \a this_left to be the same value. - - \param other_right - is the index (in the other \c sparse_set object) of the - right operand for the union operation. - It is OK for \a this_target and \a other_right to be the same value. - - \param other - is the other \c sparse_set object (which may be the same as this - \c sparse_set object). - - \par Checked Assertions - \li this_target < n_set_ - \li this_left < n_set_ - \li other_right < other.n_set_ - */ - void binary_union( - size_t this_target , - size_t this_left , - size_t other_right , - const sparse_set& other ) - { CPPAD_ASSERT_UNKNOWN( this_target < n_set_ ); - CPPAD_ASSERT_UNKNOWN( this_left < n_set_ ); - CPPAD_ASSERT_UNKNOWN( other_right < other.n_set_ ); - - // use a temporary set for holding results - // (in case target set is same as one of the other sets) - Set temp; - std::set_union( - data_[this_left].begin() , - data_[this_left].end() , - other.data_[other_right].begin() , - other.data_[other_right].end() , - std::inserter(temp, temp.begin()) - ); - - // move results to the target set with out copying elements - data_[this_target].swap(temp); - - } - // ----------------------------------------------------------------- - /*! Sum over all sets of the number of elements - - /return - The the total number of elements - */ - size_t number_elements(void) const - { size_t i, count; - count = 0; - for(i = 0; i < n_set_; i++) - count += data_[i].size(); - return count; - } - // ----------------------------------------------------------------- - /*! Fetch n_set for vector of sets object. - - \return - Number of from sets for this vector of sets object - */ - size_t n_set(void) const - { return n_set_; } - // ----------------------------------------------------------------- - /*! Fetch end for this vector of sets object. - - \return - is the maximum element value plus one (the minimum element value is 0). - */ - size_t end(void) const - { return end_; } -}; - -/*! -Copy a user vector of sets sparsity pattern to an internal sparse_set object. - -\tparam VectorSet -is a simple vector with elements of type \c std::set. - -\param internal -The input value of sparisty does not matter. -Upon return it contains the same sparsity pattern as \c user -(or the transposed sparsity pattern). - -\param user -sparsity pattern that we are placing \c internal. - -\param n_row -number of rows in the sparsity pattern in \c user -(range dimension). - -\param n_col -number of columns in the sparsity pattern in \c user -(domain dimension). - -\param transpose -if true, the sparsity pattern in \c internal is the transpose -of the one in \c user. -Otherwise it is the same sparsity pattern. -*/ -template -void sparsity_user2internal( - sparse_set& internal , - const VectorSet& user , - size_t n_row , - size_t n_col , - bool transpose ) -{ - CPPAD_ASSERT_KNOWN( - size_t( user.size() ) == n_row, - "Size of this vector of sets sparsity pattern is not equal\n" - "the range dimension for the corresponding function." - ); - - size_t i, j; - std::set::const_iterator itr; - - // transposed pattern case - if( transpose ) - { internal.resize(n_col, n_row); - for(i = 0; i < n_row; i++) - { itr = user[i].begin(); - while(itr != user[i].end()) - { j = *itr++; - CPPAD_ASSERT_KNOWN( - j < n_col, - "An element in this vector of sets sparsity pattern " - "is greater than or equal\n" - "the domain dimension for the corresponding function." - ); - internal.add_element(j, i); - } - } - return; - } - - // same pattern case - internal.resize(n_row, n_col); - for(i = 0; i < n_row; i++) - { itr = user[i].begin(); - while(itr != user[i].end()) - { j = *itr++; - CPPAD_ASSERT_UNKNOWN( j < n_col ); - internal.add_element(i, j); - } - } - return; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/sparse_unary_op.hpp b/ct_core/include/ct/external/cppad/local/sparse_unary_op.hpp deleted file mode 100644 index c5a07e2d1..000000000 --- a/ct_core/include/ct/external/cppad/local/sparse_unary_op.hpp +++ /dev/null @@ -1,209 +0,0 @@ -// $Id: sparse_unary_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SPARSE_UNARY_OP_HPP -# define CPPAD_SPARSE_UNARY_OP_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file sparse_unary_op.hpp -Forward and reverse mode sparsity patterns for unary operators. -*/ - - -/*! -Forward mode Jacobian sparsity pattern for all unary operators. - -The C++ source code corresponding to a unary operation has the form -\verbatim - z = fun(x) -\endverbatim -where fun is a C++ unary function, or it has the form -\verbatim - z = x op q -\endverbatim -where op is a C++ binary unary operator and q is a parameter. - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set or \c sparse_list. - -\param i_z -variable index corresponding to the result for this operation; -i.e., z. - -\param i_x -variable index corresponding to the argument for this operator; -i.e., x. - - -\param sparsity -\b Input: The set with index \a arg[0] in \a sparsity -is the sparsity bit pattern for x. -This identifies which of the independent variables the variable x -depends on. -\n -\n -\b Output: The set with index \a i_z in \a sparsity -is the sparsity bit pattern for z. -This identifies which of the independent variables the variable z -depends on. -\n - -\par Checked Assertions: -\li \a i_x < \a i_z -*/ - -template -inline void forward_sparse_jacobian_unary_op( - size_t i_z , - size_t i_x , - Vector_set& sparsity ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( i_x < i_z ); - - sparsity.assignment(i_z, i_x, sparsity); -} - -/*! -Reverse mode Jacobian sparsity pattern for all unary operators. - -The C++ source code corresponding to a unary operation has the form -\verbatim - z = fun(x) -\endverbatim -where fun is a C++ unary function, or it has the form -\verbatim - z = x op q -\endverbatim -where op is a C++ bianry operator and q is a parameter. - -This routine is given the sparsity patterns -for a function G(z, y, ... ) -and it uses them to compute the sparsity patterns for -\verbatim - H( x , w , u , ... ) = G[ z(x) , x , w , u , ... ] -\endverbatim - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - - -\param i_z -variable index corresponding to the result for this operation; -i.e. the row index in sparsity corresponding to z. - -\param i_x -variable index corresponding to the argument for this operator; -i.e. the row index in sparsity corresponding to x. - -\param sparsity -\b Input: -The set with index \a i_z in \a sparsity -is the sparsity bit pattern for G with respect to the variable z. -\n -\b Input: -The set with index \a i_x in \a sparsity -is the sparsity bit pattern for G with respect to the variable x. -\n -\b Output: -The set with index \a i_x in \a sparsity -is the sparsity bit pattern for H with respect to the variable x. - -\par Checked Assertions: -\li \a i_x < \a i_z -*/ - -template -inline void reverse_sparse_jacobian_unary_op( - size_t i_z , - size_t i_x , - Vector_set& sparsity ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( i_x < i_z ); - - sparsity.binary_union(i_x, i_x, i_z, sparsity); - - return; -} - -/*! -Reverse mode Hessian sparsity pattern for linear unary operators. - -The C++ source code corresponding to this operation is -\verbatim - z = fun(x) -\endverbatim -where fun is a linear functions; e.g. abs, or -\verbatim - z = x op q -\endverbatim -where op is a C++ binary operator and q is a parameter. - -\copydetails reverse_sparse_hessian_unary_op -*/ -template -inline void reverse_sparse_hessian_linear_unary_op( - size_t i_z , - size_t i_x , - bool* rev_jacobian , - Vector_set& for_jac_sparsity , - Vector_set& rev_hes_sparsity ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( i_x < i_z ); - - rev_hes_sparsity.binary_union(i_x, i_x, i_z, rev_hes_sparsity); - - rev_jacobian[i_x] |= rev_jacobian[i_z]; - return; -} - -/*! -Reverse mode Hessian sparsity pattern for non-linear unary operators. - -The C++ source code corresponding to this operation is -\verbatim - z = fun(x) -\endverbatim -where fun is a non-linear functions; e.g. sin. or -\verbatim - z = q / x -\endverbatim -where q is a parameter. - - -\copydetails reverse_sparse_hessian_unary_op -*/ -template -inline void reverse_sparse_hessian_nonlinear_unary_op( - size_t i_z , - size_t i_x , - bool* rev_jacobian , - Vector_set& for_jac_sparsity , - Vector_set& rev_hes_sparsity ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( i_x < i_z ); - - rev_hes_sparsity.binary_union(i_x, i_x, i_z, rev_hes_sparsity); - if( rev_jacobian[i_z] ) - rev_hes_sparsity.binary_union(i_x, i_x, i_x, for_jac_sparsity); - - rev_jacobian[i_x] |= rev_jacobian[i_z]; - return; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/sqrt_op.hpp b/ct_core/include/ct/external/cppad/local/sqrt_op.hpp deleted file mode 100644 index 6feb4cbcc..000000000 --- a/ct_core/include/ct/external/cppad/local/sqrt_op.hpp +++ /dev/null @@ -1,194 +0,0 @@ -// $Id: sqrt_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SQRT_OP_HPP -# define CPPAD_SQRT_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file sqrt_op.hpp -Forward and reverse mode calculations for z = sqrt(x). -*/ - - -/*! -Compute forward mode Taylor coefficient for result of op = SqrtOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sqrt(x) -\endverbatim - -\copydetails forward_unary1_op -*/ -template -inline void forward_sqrt_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SqrtOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SqrtOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - - size_t k; - if( p == 0 ) - { z[0] = sqrt( x[0] ); - p++; - } - for(size_t j = p; j <= q; j++) - { - z[j] = Base(0); - for(k = 1; k < j; k++) - z[j] -= Base(k) * z[k] * z[j-k]; - z[j] /= Base(j); - z[j] += x[j] / Base(2); - z[j] /= z[0]; - } -} - -/*! -Multiple direction forward mode Taylor coefficient for op = SqrtOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sqrt(x) -\endverbatim - -\copydetails forward_unary1_op_dir -*/ -template -inline void forward_sqrt_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SqrtOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SqrtOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* z = taylor + i_z * num_taylor_per_var; - Base* x = taylor + i_x * num_taylor_per_var; - - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - { z[m+ell] = Base(0); - for(size_t k = 1; k < q; k++) - z[m+ell] -= Base(k) * z[(k-1)*r+1+ell] * z[(q-k-1)*r+1+ell]; - z[m+ell] /= Base(q); - z[m+ell] += x[m+ell] / Base(2); - z[m+ell] /= z[0]; - } -} - -/*! -Compute zero order forward mode Taylor coefficient for result of op = SqrtOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sqrt(x) -\endverbatim - -\copydetails forward_unary1_op_0 -*/ -template -inline void forward_sqrt_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SqrtOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SqrtOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = sqrt( x[0] ); -} -/*! -Compute reverse mode partial derivatives for result of op = SqrtOp. - -The C++ source code corresponding to this operation is -\verbatim - z = sqrt(x) -\endverbatim - -\copydetails reverse_unary1_op -*/ - -template -inline void reverse_sqrt_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SqrtOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SqrtOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to result - const Base* z = taylor + i_z * cap_order; - Base* pz = partial + i_z * nc_partial; - - - Base inv_z0 = Base(1) / z[0]; - - // number of indices to access - size_t j = d; - size_t k; - while(j) - { - - // scale partial w.r.t. z[j] - pz[j] = azmul(pz[j], inv_z0); - - pz[0] -= azmul(pz[j], z[j]); - px[j] += pz[j] / Base(2); - for(k = 1; k < j; k++) - pz[k] -= azmul(pz[j], z[j-k]); - --j; - } - px[0] += azmul(pz[0], inv_z0) / Base(2); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/standard_math.hpp b/ct_core/include/ct/external/cppad/local/standard_math.hpp deleted file mode 100644 index e3bdb879b..000000000 --- a/ct_core/include/ct/external/cppad/local/standard_math.hpp +++ /dev/null @@ -1,132 +0,0 @@ -// $Id$ -# ifndef CPPAD_STANDARD_MATH_HPP -# define CPPAD_STANDARD_MATH_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin unary_standard_math$$ -$spell - const - VecAD - fabs -$$ - -$section The Unary Standard Math Functions$$ - -$head Syntax$$ -$icode%y% = %fun%(%x%)%$$ - -$head Purpose$$ -Evaluates the standard math function $icode fun$$. - -$head Possible Types$$ - -$subhead Base$$ -If $icode Base$$ satisfies the -$cref/base type requirements/base_require/$$ -and argument $icode x$$ has prototype -$codei% - const %Base%& %x% -%$$ -then the result $icode y$$ has prototype -$codei% - %Base% %y% -%$$ - -$subhead AD$$ -If the argument $icode x$$ has prototype -$codei% - const AD<%Base%>& %x% -%$$ -then the result $icode y$$ has prototype -$codei% - AD<%Base%> %y% -%$$ - -$subhead VecAD$$ -If the argument $icode x$$ has prototype -$codei% - const VecAD<%Base%>::reference& %x% -%$$ -then the result $icode y$$ has prototype -$codei% - AD<%Base%> %y% -%$$ - -$children%cppad/local/std_math_98.hpp - %cppad/local/abs.hpp - %cppad/local/acosh.hpp - %cppad/local/asinh.hpp - %cppad/local/atanh.hpp - %cppad/local/erf.hpp - %cppad/local/expm1.hpp - %cppad/local/log1p.hpp - %cppad/local/sign.hpp -%$$ - -$head fun$$ -The possible values for $icode fun$$ are -$table -$icode fun$$ $pre $$ $cnext Description $rnext -$cref abs$$ $cnext $title abs$$ $rnext -$cref acos$$ $cnext $title acos$$ $rnext -$cref acosh$$ $cnext $title acosh$$ $rnext -$cref asin$$ $cnext $title asin$$ $rnext -$cref asinh$$ $cnext $title asinh$$ $rnext -$cref atan$$ $cnext $title atan$$ $rnext -$cref atanh$$ $cnext $title atanh$$ $rnext -$cref cos$$ $cnext $title cos$$ $rnext -$cref cosh$$ $cnext $title cosh$$ $rnext -$cref erf$$ $cnext $title erf$$ $rnext -$cref exp$$ $cnext $title exp$$ $rnext -$cref expm1$$ $cnext $title expm1$$ $rnext -$cref/fabs/abs/$$ $cnext $title abs$$ $rnext -$cref log10$$ $cnext $title log10$$ $rnext -$cref log1p$$ $cnext $title log1p$$ $rnext -$cref log$$ $cnext $title log$$ $rnext -$cref sign$$ $cnext $title sign$$ $rnext -$cref sin$$ $cnext $title sin$$ $rnext -$cref sinh$$ $cnext $title sinh$$ $rnext -$cref sqrt$$ $cnext $title sqrt$$ $rnext -$cref tan$$ $cnext $title tan$$ $rnext -$cref tanh$$ $cnext $title tanh$$ -$tend - -$end -*/ -# include -# include -# include -# include -# include -# include -# include -# include -# include - -/* -$begin binary_math$$ - -$section The Binary Math Functions$$ - -$childtable%cppad/local/atan2.hpp - %cppad/local/pow.hpp - %cppad/local/azmul.hpp -%$$ - -$end -*/ -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/local/std_math_98.hpp b/ct_core/include/ct/external/cppad/local/std_math_98.hpp deleted file mode 100644 index 509894aad..000000000 --- a/ct_core/include/ct/external/cppad/local/std_math_98.hpp +++ /dev/null @@ -1,601 +0,0 @@ -// $Id$ -# ifndef CPPAD_STD_MATH_98_HPP -# define CPPAD_STD_MATH_98_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -------------------------------------------------------------------------------- -$begin acos$$ -$spell - acos -$$ - -$section Inverse Sine Function: acos$$ - -$head Syntax$$ -$icode%y% = acos(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{acos}^{(1)} (x) & = & - (1 - x * x)^{-1/2} -\end{array} -\] $$ - -$head Example$$ -$children% - example/acos.cpp -%$$ -The file -$cref acos.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin asin$$ -$spell - asin -$$ - -$section Inverse Sine Function: asin$$ - -$head Syntax$$ -$icode%y% = asin(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{asin}^{(1)} (x) & = & (1 - x * x)^{-1/2} -\end{array} -\] $$ - -$head Example$$ -$children% - example/asin.cpp -%$$ -The file -$cref asin.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin atan$$ -$spell - atan -$$ - -$section Inverse Tangent Function: atan$$ - -$head Syntax$$ -$icode%y% = atan(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{atan}^{(1)} (x) & = & \frac{1}{1 + x^2} -\end{array} -\] $$ - -$head Example$$ -$children% - example/atan.cpp -%$$ -The file -$cref atan.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin cos$$ -$spell - cos -$$ - -$section The Cosine Function: cos$$ - -$head Syntax$$ -$icode%y% = cos(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{cos}^{(1)} (x) & = & - \sin(x) -\end{array} -\] $$ - -$head Example$$ -$children% - example/cos.cpp -%$$ -The file -$cref cos.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin cosh$$ -$spell - cosh -$$ - -$section The Hyperbolic Cosine Function: cosh$$ - -$head Syntax$$ -$icode%y% = cosh(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{cosh}^{(1)} (x) & = & \sinh(x) -\end{array} -\] $$ - -$head Example$$ -$children% - example/cosh.cpp -%$$ -The file -$cref cosh.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin exp$$ -$spell - exp -$$ - -$section The Exponential Function: exp$$ - -$head Syntax$$ -$icode%y% = exp(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{exp}^{(1)} (x) & = & \exp(x) -\end{array} -\] $$ - -$head Example$$ -$children% - example/exp.cpp -%$$ -The file -$cref exp.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin log$$ -$spell -$$ - -$section The Exponential Function: log$$ - -$head Syntax$$ -$icode%y% = log(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{log}^{(1)} (x) & = & \frac{1}{x} -\end{array} -\] $$ - -$head Example$$ -$children% - example/log.cpp -%$$ -The file -$cref log.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin log10$$ -$spell - CppAD -$$ - -$section The Base 10 Logarithm Function: log10$$ - -$head Syntax$$ -$icode%y% = log10(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Method$$ -CppAD uses the representation -$latex \[ -\begin{array}{lcr} - {\rm log10} (x) & = & \log(x) / \log(10) -\end{array} -\] $$ - -$head Example$$ -$children% - example/log10.cpp -%$$ -The file -$cref log10.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin sin$$ -$spell - sin -$$ - -$section The Sine Function: sin$$ - -$head Syntax$$ -$icode%y% = sin(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{sin}^{(1)} (x) & = & \cos(x) -\end{array} -\] $$ - -$head Example$$ -$children% - example/sin.cpp -%$$ -The file -$cref sin.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin sinh$$ -$spell - sinh -$$ - -$section The Hyperbolic Sine Function: sinh$$ - -$head Syntax$$ -$icode%y% = sinh(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{sinh}^{(1)} (x) & = & \cosh(x) -\end{array} -\] $$ - -$head Example$$ -$children% - example/sinh.cpp -%$$ -The file -$cref sinh.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin sqrt$$ -$spell - sqrt -$$ - -$section The Square Root Function: sqrt$$ - -$head Syntax$$ -$icode%y% = sqrt(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{sqrt}^{(1)} (x) & = & \frac{1}{2 \R{sqrt} (x) } -\end{array} -\] $$ - -$head Example$$ -$children% - example/sqrt.cpp -%$$ -The file -$cref sqrt.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin tan$$ -$spell - tan -$$ - -$section The Tangent Function: tan$$ - -$head Syntax$$ -$icode%y% = tan(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{tan}^{(1)} (x) & = & 1 + \tan (x)^2 -\end{array} -\] $$ - -$head Example$$ -$children% - example/tan.cpp -%$$ -The file -$cref tan.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -$begin tanh$$ -$spell - tanh -$$ - -$section The Hyperbolic Tangent Function: tanh$$ - -$head Syntax$$ -$icode%y% = tanh(%x%)%$$ - -$head x, y$$ -See the $cref/possible types/unary_standard_math/Possible Types/$$ -for a unary standard math function. - -$head Atomic$$ -This is an $cref/atomic operation/glossary/Operation/Atomic/$$. - -$head Derivative$$ -$latex \[ -\begin{array}{lcr} - \R{tanh}^{(1)} (x) & = & 1 - \tanh (x)^2 -\end{array} -\] $$ - -$head Example$$ -$children% - example/tanh.cpp -%$$ -The file -$cref tanh.cpp$$ -contains an example and test of this function. -It returns true if it succeeds and false otherwise. - -$end -------------------------------------------------------------------------------- -*/ - -/*! -\file std_math_98.hpp -Define AD standard math functions (using their Base versions) -*/ - -/*! -\def CPPAD_STANDARD_MATH_UNARY_AD(Name, Op) -Defines function Name with argument type AD and tape operation Op - -The macro defines the function x.Name() where x has type AD. -It then uses this funciton to define Name(x) where x has type -AD or VecAD_reference. - -If x is a variable, the tape unary operator Op is used -to record the operation and the result is identified as correspoding -to this operation; i.e., Name(x).taddr_ idendifies the operation and -Name(x).tape_id_ identifies the tape. - -This macro is used to define AD versions of -acos, asin, atan, cos, cosh, exp, fabs, log, sin, sinh, sqrt, tan, tanh. -*/ - -# define CPPAD_STANDARD_MATH_UNARY_AD(Name, Op) \ - template \ - inline AD Name(const AD &x) \ - { return x.Name(); } \ - template \ - inline AD AD::Name (void) const \ - { \ - AD result; \ - result.value_ = CppAD::Name(value_); \ - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); \ - \ - if( Variable(*this) ) \ - { CPPAD_ASSERT_UNKNOWN( NumArg(Op) == 1 ); \ - ADTape *tape = tape_this(); \ - tape->Rec_.PutArg(taddr_); \ - result.taddr_ = tape->Rec_.PutOp(Op); \ - result.tape_id_ = tape->id_; \ - } \ - return result; \ - } \ - template \ - inline AD Name(const VecAD_reference &x) \ - { return Name( x.ADBase() ); } - -// BEGIN CppAD namespace -namespace CppAD { - - CPPAD_STANDARD_MATH_UNARY_AD(acos, AcosOp) - CPPAD_STANDARD_MATH_UNARY_AD(asin, AsinOp) - CPPAD_STANDARD_MATH_UNARY_AD(atan, AtanOp) - CPPAD_STANDARD_MATH_UNARY_AD(cos, CosOp) - CPPAD_STANDARD_MATH_UNARY_AD(cosh, CoshOp) - CPPAD_STANDARD_MATH_UNARY_AD(exp, ExpOp) - CPPAD_STANDARD_MATH_UNARY_AD(fabs, AbsOp) - CPPAD_STANDARD_MATH_UNARY_AD(log, LogOp) - CPPAD_STANDARD_MATH_UNARY_AD(sin, SinOp) - CPPAD_STANDARD_MATH_UNARY_AD(sinh, SinhOp) - CPPAD_STANDARD_MATH_UNARY_AD(sqrt, SqrtOp) - CPPAD_STANDARD_MATH_UNARY_AD(tan, TanOp) - CPPAD_STANDARD_MATH_UNARY_AD(tanh, TanhOp) - -# if CPPAD_USE_CPLUSPLUS_2011 - CPPAD_STANDARD_MATH_UNARY_AD(asinh, AsinhOp) - CPPAD_STANDARD_MATH_UNARY_AD(acosh, AcoshOp) - CPPAD_STANDARD_MATH_UNARY_AD(atanh, AtanhOp) - CPPAD_STANDARD_MATH_UNARY_AD(expm1, Expm1Op) - CPPAD_STANDARD_MATH_UNARY_AD(log1p, Log1pOp) -# endif - -# if CPPAD_USE_CPLUSPLUS_2011 - // Error function is a special case - template - inline AD erf(const AD &x) - { return x.erf(); } - template - inline AD AD::erf (void) const - { - AD result; - result.value_ = CppAD::erf(value_); - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - if( Variable(*this) ) - { CPPAD_ASSERT_UNKNOWN( NumArg(ErfOp) == 3 ); - ADTape *tape = tape_this(); - // arg[0] = argument to erf function - tape->Rec_.PutArg(taddr_); - // arg[1] = zero - addr_t p = tape->Rec_.PutPar( Base(0) ); - tape->Rec_.PutArg(p); - // arg[2] = 2 / sqrt(pi) - p = tape->Rec_.PutPar(Base( - 1.0 / std::sqrt( std::atan(1.0) ) - )); - tape->Rec_.PutArg(p); - // - result.taddr_ = tape->Rec_.PutOp(ErfOp); - result.tape_id_ = tape->id_; - } - return result; - } - template - inline AD erf(const VecAD_reference &x) - { return erf( x.ADBase() ); } -# endif - - /*! - Compute the log of base 10 of x where has type AD - - \tparam Base - is the base type (different from base for log) - for this AD type, see base_require. - - \param x - is the argument for the log10 function. - - \result - if the result is y, then \f$ x = 10^y \f$. - */ - template - inline AD log10(const AD &x) - { return CppAD::log(x) / CppAD::log( Base(10) ); } - template - inline AD log10(const VecAD_reference &x) - { return CppAD::log(x.ADBase()) / CppAD::log( Base(10) ); } -} - -# undef CPPAD_STANDARD_MATH_UNARY_AD - -# endif diff --git a/ct_core/include/ct/external/cppad/local/std_set.hpp b/ct_core/include/ct/external/cppad/local/std_set.hpp deleted file mode 100644 index 0e459c009..000000000 --- a/ct_core/include/ct/external/cppad/local/std_set.hpp +++ /dev/null @@ -1,53 +0,0 @@ -// $Id: std_set.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_STD_SET_HPP -# define CPPAD_STD_SET_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include - -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file std_set.hpp -Two constant standard sets (currently used for concept checking). -*/ - -/*! -A standard set with one element. -*/ -template -const std::set& one_element_std_set(void) -{ CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static std::set one; - if( one.empty() ) - one.insert(1); - return one; -} -/*! -A standard set with a two elements. -*/ -template -const std::set& two_element_std_set(void) -{ CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static std::set two; - if( two.empty() ) - { two.insert(1); - two.insert(2); - } - return two; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/store_op.hpp b/ct_core/include/ct/external/cppad/local/store_op.hpp deleted file mode 100644 index d7f34fb2f..000000000 --- a/ct_core/include/ct/external/cppad/local/store_op.hpp +++ /dev/null @@ -1,498 +0,0 @@ -// $Id: store_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_STORE_OP_HPP -# define CPPAD_STORE_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file store_op.hpp -Changing the current value of a VecAD element. -*/ -/* -============================================================================== - -The C++ source code corresponding to this operation is -\verbatim - v[x] = y -\endverbatim -where v is a VecAD vector, x is an AD object, -and y is AD or Base objects. -We define the index corresponding to v[x] by -\verbatim - i_v_x = index_by_ind[ arg[0] + i_vec ] -\endverbatim -where i_vec is defined under the heading arg[1] below: - -============================================================================== -*/ -/*! -Shared documentation for zero order forward implementation of -op = StppOp, StpvOp, StvpOp, or StvvOp (not called). - - -The C++ source code corresponding to this operation is -\verbatim - v[x] = y -\endverbatim -where v is a VecAD vector, x is an AD object, -and y is AD or Base objects. -We define the index corresponding to v[x] by -\verbatim - i_v_x = index_by_ind[ arg[0] + i_vec ] -\endverbatim -where i_vec is defined under the heading arg[1] below: - - -\tparam Base -base type for the operator; i.e., this operation was recorded -using AD and computations by this routine are done using type Base. - -\param i_z -is the index corresponding to the previous variable on the tape -(only used for error checking). - -\param arg -\n -arg[0] -\n -is the offset of this VecAD vector relative to the beginning -of the isvar_by_ind and index_by_ind arrays. -\n -\n -arg[1] -\n -If this is a StppOp or StpvOp operation (if x is a parameter), -i_vec is defined by -\verbatim - i_vec = arg[1] -\endverbatim -If this is a StvpOp or StvvOp operation (if x is a variable), -i_vec is defined by -\verbatim - i_vec = floor( taylor[ arg[1] * cap_order + 0 ] ) -\endverbatim -where floor(c) is the greatest integer less that or equal c. -\n -\n -arg[2] -\n -index corresponding to the third operand for this operator; -i.e. the index corresponding to y. - -\param num_par -is the total number of parameters on the tape -(only used for error checking). - -\param cap_order -number of columns in the matrix containing the Taylor coefficients. - -\param taylor -In StvpOp and StvvOp cases, -is used to compute the index in the definition of i_vec above. - -\param isvar_by_ind -If y is a varable (StpvOp and StvvOp cases), -isvar_by_ind[ arg[0] + i_vec ] is set to true. -Otherwise y is a paraemter (StppOp and StvpOp cases) and -isvar_by_ind[ arg[0] + i_vec ] is set to false. - -\param index_by_ind -index_by_ind[ arg[0] - 1 ] -is the number of elements in the user vector containing this element. -The value index_by_ind[ arg[0] + i_vec] -is set equal to arg[2]. - -\par Check User Errors -\li Check that the index is with in range; i.e. -i_vec < index_by_ind[ arg[0] - 1 ] -Note that, if x is a parameter, -the corresponding vector index and it does not change. -In this case, the error above should be detected during tape recording. - -\par Checked Assertions -\li NumArg(op) == 3 -\li NumRes(op) == 0 -\li 0 < arg[0] -\li if y is a parameter, arg[2] < num_par -*/ -template -inline void forward_store_op_0( - size_t i_z , - const addr_t* arg , - size_t num_par , - size_t cap_order , - Base* taylor , - bool* isvar_by_ind , - size_t* index_by_ind ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} -/*! -Shared documnetation for sparsity operations corresponding to -op = StpvOp or StvvOp (not called). - -\tparam Vector_set -is the type used for vectors of sets. It can be either -\c sparse_pack, \c sparse_set, or \c sparse_list. - -\param op -is the code corresponding to this operator; -i.e., StpvOp, StvpOp, or StvvOp. - -\param arg -\n -\a arg[0] -is the offset corresponding to this VecAD vector in the combined array. -\n -\n -\a arg[2] -\n -The set with index \a arg[2] in \a var_sparsity -is the sparsity pattern corresponding to y. -(Note that \a arg[2] > 0 because y is a variable.) - -\param num_combined -is the total number of elements in the VecAD address array. - -\param combined -\a combined [ arg[0] - 1 ] -is the index of the set in \a vecad_sparsity corresponding -to the sparsity pattern for the vector v. -We use the notation i_v below which is defined by -\verbatim - i_v = combined[ \a arg[0] - 1 ] -\endverbatim - -\param var_sparsity -The set with index \a arg[2] in \a var_sparsity -is the sparsity pattern for y. -This is an input for forward mode operations. -For reverse mode operations: -The sparsity pattern for v is added to the spartisy pattern for y. - -\param vecad_sparsity -The set with index \a i_v in \a vecad_sparsity -is the sparsity pattern for v. -This is an input for reverse mode operations. -For forward mode operations, the sparsity pattern for y is added -to the sparsity pattern for the vector v. - -\par Checked Assertions -\li NumArg(op) == 3 -\li NumRes(op) == 0 -\li 0 < \a arg[0] -\li \a arg[0] < \a num_combined -\li \a arg[2] < \a var_sparsity.n_set() -\li i_v < \a vecad_sparsity.n_set() -*/ -template -inline void sparse_store_op( - OpCode op , - const addr_t* arg , - size_t num_combined , - const size_t* combined , - Vector_set& var_sparsity , - Vector_set& vecad_sparsity ) -{ - // This routine is only for documentaiton, it should not be used - CPPAD_ASSERT_UNKNOWN( false ); -} - - -/*! -Zero order forward mode implementation of op = StppOp. - -\copydetails forward_store_op_0 -*/ -template -inline void forward_store_pp_op_0( - size_t i_z , - const addr_t* arg , - size_t num_par , - size_t cap_order , - Base* taylor , - bool* isvar_by_ind , - size_t* index_by_ind ) -{ size_t i_vec = arg[1]; - - // Because the index is a parameter, this indexing error should be - // caught and reported to the user when the tape is recording. - CPPAD_ASSERT_UNKNOWN( i_vec < index_by_ind[ arg[0] - 1 ] ); - - CPPAD_ASSERT_UNKNOWN( NumArg(StppOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(StppOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < num_par ); - - isvar_by_ind[ arg[0] + i_vec ] = false; - index_by_ind[ arg[0] + i_vec ] = arg[2]; -} - -/*! -Zero order forward mode implementation of op = StpvOp. - -\copydetails forward_store_op_0 -*/ -template -inline void forward_store_pv_op_0( - size_t i_z , - const addr_t* arg , - size_t num_par , - size_t cap_order , - Base* taylor , - bool* isvar_by_ind , - size_t* index_by_ind ) -{ size_t i_vec = arg[1]; - - // Because the index is a parameter, this indexing error should be - // caught and reported to the user when the tape is recording. - CPPAD_ASSERT_UNKNOWN( i_vec < index_by_ind[ arg[0] - 1 ] ); - - CPPAD_ASSERT_UNKNOWN( NumArg(StpvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(StpvOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - - isvar_by_ind[ arg[0] + i_vec ] = true; - index_by_ind[ arg[0] + i_vec ] = arg[2]; -} - -/*! -Zero order forward mode implementation of op = StvpOp. - -\copydetails forward_store_op_0 -*/ -template -inline void forward_store_vp_op_0( - size_t i_z , - const addr_t* arg , - size_t num_par , - size_t cap_order , - Base* taylor , - bool* isvar_by_ind , - size_t* index_by_ind ) -{ - size_t i_vec = Integer( taylor[ arg[1] * cap_order + 0 ] ); - CPPAD_ASSERT_KNOWN( - i_vec < index_by_ind[ arg[0] - 1 ] , - "VecAD: index during zero order forward sweep is out of range" - ); - - CPPAD_ASSERT_UNKNOWN( NumArg(StvpOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(StvpOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < num_par ); - - isvar_by_ind[ arg[0] + i_vec ] = false; - index_by_ind[ arg[0] + i_vec ] = arg[2]; -} - -/*! -Zero order forward mode implementation of op = StvvOp. - -\copydetails forward_store_op_0 -*/ -template -inline void forward_store_vv_op_0( - size_t i_z , - const addr_t* arg , - size_t num_par , - size_t cap_order , - Base* taylor , - bool* isvar_by_ind , - size_t* index_by_ind ) -{ - size_t i_vec = Integer( taylor[ arg[1] * cap_order + 0 ] ); - CPPAD_ASSERT_KNOWN( - i_vec < index_by_ind[ arg[0] - 1 ] , - "VecAD: index during zero order forward sweep is out of range" - ); - - CPPAD_ASSERT_UNKNOWN( NumArg(StvpOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(StvpOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - - isvar_by_ind[ arg[0] + i_vec ] = true; - index_by_ind[ arg[0] + i_vec ] = arg[2]; -} - -/*! -Forward mode sparsity operations for StpvOp and StvvOp - - -The C++ source code corresponding to this operation is -\verbatim - v[x] = y -\endverbatim -where v is a VecAD vector, x is an AD object, -and y is AD or Base objects. -We define the index corresponding to v[x] by -\verbatim - i_v_x = index_by_ind[ arg[0] + i_vec ] -\endverbatim -where i_vec is defined under the heading arg[1] below: - - -\param dependency -is this a dependency (or sparsity) calculation. - -\copydetails sparse_store_op -*/ -template -inline void forward_sparse_store_op( - bool dependency , - OpCode op , - const addr_t* arg , - size_t num_combined , - const size_t* combined , - Vector_set& var_sparsity , - Vector_set& vecad_sparsity ) -{ - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 0 ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_combined ); - size_t i_v = combined[ arg[0] - 1 ]; - CPPAD_ASSERT_UNKNOWN( i_v < vecad_sparsity.n_set() ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < var_sparsity.n_set() ); - - if( dependency & ( (op == StvvOp) | (op == StvpOp) ) ) - vecad_sparsity.binary_union(i_v, i_v, arg[1], var_sparsity); - - if( (op == StpvOp) | (op == StvvOp ) ) - vecad_sparsity.binary_union(i_v, i_v, arg[2], var_sparsity); - - return; -} - -/*! -Reverse mode sparsity operations for StpvOp, StvpOp, and StvvOp - - -The C++ source code corresponding to this operation is -\verbatim - v[x] = y -\endverbatim -where v is a VecAD vector, x is an AD object, -and y is AD or Base objects. -We define the index corresponding to v[x] by -\verbatim - i_v_x = index_by_ind[ arg[0] + i_vec ] -\endverbatim -where i_vec is defined under the heading arg[1] below: - - -This routine is given the sparsity patterns for -G(v[x], y , w , u ... ) and it uses them to compute the -sparsity patterns for -\verbatim - H(y , w , u , ... ) = G[ v[x], y , w , u , ... ] -\endverbatim - -\param dependency -is this a dependency (or sparsity) calculation. - -\copydetails sparse_store_op -*/ -template -inline void reverse_sparse_jacobian_store_op( - bool dependency , - OpCode op , - const addr_t* arg , - size_t num_combined , - const size_t* combined , - Vector_set& var_sparsity , - Vector_set& vecad_sparsity ) -{ - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 0 ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_combined ); - size_t i_v = combined[ arg[0] - 1 ]; - CPPAD_ASSERT_UNKNOWN( i_v < vecad_sparsity.n_set() ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < var_sparsity.n_set() ); - - if( dependency & ( (op == StvpOp) | (op == StvvOp) ) ) - var_sparsity.binary_union(arg[1], arg[1], i_v, vecad_sparsity); - if( (op == StpvOp) | (op == StvvOp) ) - var_sparsity.binary_union(arg[2], arg[2], i_v, vecad_sparsity); - - return; -} - -/*! -Reverse mode sparsity operations for StpvOp and StvvOp - - -The C++ source code corresponding to this operation is -\verbatim - v[x] = y -\endverbatim -where v is a VecAD vector, x is an AD object, -and y is AD or Base objects. -We define the index corresponding to v[x] by -\verbatim - i_v_x = index_by_ind[ arg[0] + i_vec ] -\endverbatim -where i_vec is defined under the heading arg[1] below: - - -This routine is given the sparsity patterns for -G(v[x], y , w , u ... ) -and it uses them to compute the sparsity patterns for -\verbatim - H(y , w , u , ... ) = G[ v[x], y , w , u , ... ] -\endverbatim - -\copydetails sparse_store_op - -\param var_jacobian -\a var_jacobian[ \a arg[2] ] -is false (true) if the Jacobian of G with respect to y is always zero -(may be non-zero). - -\param vecad_jacobian -\a vecad_jacobian[i_v] -is false (true) if the Jacobian with respect to x is always zero -(may be non-zero). -On input, it corresponds to the function G, -and on output it corresponds to the function H. -*/ -template -inline void reverse_sparse_hessian_store_op( - OpCode op , - const addr_t* arg , - size_t num_combined , - const size_t* combined , - Vector_set& var_sparsity , - Vector_set& vecad_sparsity , - bool* var_jacobian , - bool* vecad_jacobian ) -{ - CPPAD_ASSERT_UNKNOWN( NumArg(op) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(op) == 0 ); - CPPAD_ASSERT_UNKNOWN( 0 < arg[0] ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[0]) < num_combined ); - size_t i_v = combined[ arg[0] - 1 ]; - CPPAD_ASSERT_UNKNOWN( i_v < vecad_sparsity.n_set() ); - CPPAD_ASSERT_UNKNOWN( size_t(arg[2]) < var_sparsity.n_set() ); - - var_sparsity.binary_union(arg[2], arg[2], i_v, vecad_sparsity); - - var_jacobian[ arg[2] ] |= vecad_jacobian[i_v]; - - return; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/sub.hpp b/ct_core/include/ct/external/cppad/local/sub.hpp deleted file mode 100644 index e01750827..000000000 --- a/ct_core/include/ct/external/cppad/local/sub.hpp +++ /dev/null @@ -1,90 +0,0 @@ -// $Id: sub.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SUB_HPP -# define CPPAD_SUB_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD operator - (const AD &left , const AD &right) -{ - // compute the Base part - AD result; - result.value_ = left.value_ - right.value_; - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - - // check if there is a recording in progress - ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return result; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = left.tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // result = variable - variable - CPPAD_ASSERT_UNKNOWN( NumRes(SubvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(SubvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(left.taddr_, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(SubvvOp); - // make result a variable - result.tape_id_ = tape_id; - } - else if( IdenticalZero(right.value_) ) - { // result = variable - 0 - result.make_variable(left.tape_id_, left.taddr_); - } - else - { // result = variable - parameter - CPPAD_ASSERT_UNKNOWN( NumRes(SubvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(SubvpOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(left.taddr_, p); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(SubvpOp); - // make result a variable - result.tape_id_ = tape_id; - } - } - else if( var_right ) - { // result = parameter - variable - CPPAD_ASSERT_UNKNOWN( NumRes(SubpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(SubpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left.value_); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - result.taddr_ = tape->Rec_.PutOp(SubpvOp); - // make result a variable - result.tape_id_ = tape_id; - } - return result; -} - -// convert other cases into the case above -CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR(-) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/sub_eq.hpp b/ct_core/include/ct/external/cppad/local/sub_eq.hpp deleted file mode 100644 index d3b88917e..000000000 --- a/ct_core/include/ct/external/cppad/local/sub_eq.hpp +++ /dev/null @@ -1,88 +0,0 @@ -// $Id: sub_eq.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SUB_EQ_HPP -# define CPPAD_SUB_EQ_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -// BEGIN CppAD namespace -namespace CppAD { - -template -AD& AD::operator -= (const AD &right) -{ - // compute the Base part - Base left; - left = value_; - value_ -= right.value_; - - // check if there is a recording in progress - ADTape* tape = AD::tape_ptr(); - if( tape == CPPAD_NULL ) - return *this; - tape_id_t tape_id = tape->id_; - - // tape_id cannot match the default value for tape_id_; i.e., 0 - CPPAD_ASSERT_UNKNOWN( tape_id > 0 ); - bool var_left = tape_id_ == tape_id; - bool var_right = right.tape_id_ == tape_id; - - if( var_left ) - { if( var_right ) - { // this = variable - variable - CPPAD_ASSERT_UNKNOWN( NumRes(SubvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(SubvvOp) == 2 ); - - // put operand addresses in tape - tape->Rec_.PutArg(taddr_, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(SubvvOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - else if( IdenticalZero( right.value_ ) ) - { // this = variable - 0 - } - else - { // this = variable - parameter - CPPAD_ASSERT_UNKNOWN( NumRes(SubvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(SubvpOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(right.value_); - tape->Rec_.PutArg(taddr_, p); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(SubvpOp); - // make this a variable - CPPAD_ASSERT_UNKNOWN( tape_id_ == tape_id ); - } - } - else if( var_right ) - { // this = parameter - variable - CPPAD_ASSERT_UNKNOWN( NumRes(SubpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(SubpvOp) == 2 ); - - // put operand addresses in tape - addr_t p = tape->Rec_.PutPar(left); - tape->Rec_.PutArg(p, right.taddr_); - // put operator in the tape - taddr_ = tape->Rec_.PutOp(SubpvOp); - // make this a variable - tape_id_ = tape_id; - } - return *this; -} - -CPPAD_FOLD_ASSIGNMENT_OPERATOR(-=) - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/sub_op.hpp b/ct_core/include/ct/external/cppad/local/sub_op.hpp deleted file mode 100644 index c4666f8b8..000000000 --- a/ct_core/include/ct/external/cppad/local/sub_op.hpp +++ /dev/null @@ -1,501 +0,0 @@ -// $Id: sub_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SUB_OP_HPP -# define CPPAD_SUB_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file sub_op.hpp -Forward and reverse mode calculations for z = x - y. -*/ - -// --------------------------- Subvv ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = SubvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x - y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_binary_op -*/ - -template -inline void forward_subvv_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SubvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SubvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - for(size_t d = p; d <= q; d++) - z[d] = x[d] - y[d]; -} -/*! -Multiple directions forward mode Taylor coefficients for op = SubvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x - y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_binary_op_dir -*/ - -template -inline void forward_subvv_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SubvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SubvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to arguments and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - size_t m = (q-1) * r + 1; - Base* x = taylor + arg[0] * num_taylor_per_var + m; - Base* y = taylor + arg[1] * num_taylor_per_var + m; - Base* z = taylor + i_z * num_taylor_per_var + m; - - for(size_t ell = 0; ell < r; ell++) - z[ell] = x[ell] - y[ell]; -} - -/*! -Compute zero order forward mode Taylor coefficients for result of op = SubvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x - y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_binary_op_0 -*/ - -template -inline void forward_subvv_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SubvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SubvvOp) == 1 ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = x[0] - y[0]; -} - -/*! -Compute reverse mode partial derivatives for result of op = SubvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x - y -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails reverse_binary_op -*/ - -template -inline void reverse_subvv_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SubvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SubvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Partial derivatives corresponding to arguments and result - Base* px = partial + arg[0] * nc_partial; - Base* py = partial + arg[1] * nc_partial; - Base* pz = partial + i_z * nc_partial; - - // number of indices to access - size_t i = d + 1; - while(i) - { --i; - px[i] += pz[i]; - py[i] -= pz[i]; - } -} - -// --------------------------- Subpv ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = SubpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x - y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op -*/ - -template -inline void forward_subpv_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SubpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SubpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to arguments and result - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - // Paraemter value - Base x = parameter[ arg[0] ]; - if( p == 0 ) - { z[0] = x - y[0]; - p++; - } - for(size_t d = p; d <= q; d++) - z[d] = - y[d]; -} -/*! -Multiple directions forward mode Taylor coefficients for op = SubpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x - y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op_dir -*/ - -template -inline void forward_subpv_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SubpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SubpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to arguments and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - size_t m = (q-1) * r + 1; - Base* y = taylor + arg[1] * num_taylor_per_var + m; - Base* z = taylor + i_z * num_taylor_per_var + m; - - // Paraemter value - for(size_t ell = 0; ell < r; ell++) - z[ell] = - y[ell]; -} -/*! -Compute zero order forward mode Taylor coefficient for result of op = SubpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x - y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op_0 -*/ - -template -inline void forward_subpv_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SubpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SubpvOp) == 1 ); - - // Paraemter value - Base x = parameter[ arg[0] ]; - - // Taylor coefficients corresponding to arguments and result - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = x - y[0]; -} - -/*! -Compute reverse mode partial derivative for result of op = SubpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x - y -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails reverse_binary_op -*/ - -template -inline void reverse_subpv_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SubvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SubvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Partial derivatives corresponding to arguments and result - Base* py = partial + arg[1] * nc_partial; - Base* pz = partial + i_z * nc_partial; - - // number of indices to access - size_t i = d + 1; - while(i) - { --i; - py[i] -= pz[i]; - } -} - -// --------------------------- Subvp ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = SubvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x - y -\endverbatim -In the documentation below, -this operations is for the case where x is a variable and y is a parameter. - -\copydetails forward_binary_op -*/ - -template -inline void forward_subvp_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SubvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SubvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* z = taylor + i_z * cap_order; - - // Parameter value - Base y = parameter[ arg[1] ]; - if( p == 0 ) - { z[0] = x[0] - y; - p++; - } - for(size_t d = p; d <= q; d++) - z[d] = x[d]; -} -/*! -Multiple directions forward mode Taylor coefficients for op = SubvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x - y -\endverbatim -In the documentation below, -this operations is for the case where x is a variable and y is a parameter. - -\copydetails forward_binary_op_dir -*/ - -template -inline void forward_subvp_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SubvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SubvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to arguments and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + arg[0] * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - - // Parameter value - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - z[m+ell] = x[m+ell]; -} - -/*! -Compute zero order forward mode Taylor coefficients for result of op = SubvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x - y -\endverbatim -In the documentation below, -this operations is for the case where x is a variable and y is a parameter. - -\copydetails forward_binary_op_0 -*/ - -template -inline void forward_subvp_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SubvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SubvpOp) == 1 ); - - // Parameter value - Base y = parameter[ arg[1] ]; - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = x[0] - y; -} - -/*! -Compute reverse mode partial derivative for result of op = SubvpOp. - -The C++ source code corresponding to this operation is -\verbatim - z = x - y -\endverbatim -In the documentation below, -this operations is for the case where x is a variable and y is a parameter. - -\copydetails reverse_binary_op -*/ - -template -inline void reverse_subvp_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(SubvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(SubvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Partial derivatives corresponding to arguments and result - Base* px = partial + arg[0] * nc_partial; - Base* pz = partial + i_z * nc_partial; - - // number of indices to access - size_t i = d + 1; - while(i) - { --i; - px[i] += pz[i]; - } -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/tan_op.hpp b/ct_core/include/ct/external/cppad/local/tan_op.hpp deleted file mode 100644 index a1fc434d9..000000000 --- a/ct_core/include/ct/external/cppad/local/tan_op.hpp +++ /dev/null @@ -1,232 +0,0 @@ -// $Id: tan_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_TAN_OP_HPP -# define CPPAD_TAN_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file tan_op.hpp -Forward and reverse mode calculations for z = tan(x). -*/ - - -/*! -Compute forward mode Taylor coefficient for result of op = TanOp. - -The C++ source code corresponding to this operation is -\verbatim - z = tan(x) -\endverbatim -The auxillary result is -\verbatim - y = tan(x)^2 -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op -*/ -template -inline void forward_tan_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(TanOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(TanOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - Base* y = z - cap_order; - - size_t k; - if( p == 0 ) - { z[0] = tan( x[0] ); - y[0] = z[0] * z[0]; - p++; - } - for(size_t j = p; j <= q; j++) - { Base base_j = static_cast(j); - - z[j] = x[j]; - for(k = 1; k <= j; k++) - z[j] += Base(k) * x[k] * y[j-k] / base_j; - - y[j] = z[0] * z[j]; - for(k = 1; k <= j; k++) - y[j] += z[k] * z[j-k]; - } -} - -/*! -Multiple directions forward mode Taylor coefficient for op = TanOp. - -The C++ source code corresponding to this operation is -\verbatim - z = tan(x) -\endverbatim -The auxillary result is -\verbatim - y = tan(x)^2 -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op_dir -*/ -template -inline void forward_tan_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(TanOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(TanOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - Base* y = z - num_taylor_per_var; - - size_t k; - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - { z[m+ell] = Base(q) * ( x[m+ell] + x[m+ell] * y[0]); - for(k = 1; k < q; k++) - z[m+ell] += Base(k) * x[(k-1)*r+1+ell] * y[(q-k-1)*r+1+ell]; - z[m+ell] /= Base(q); - // - y[m+ell] = Base(2) * z[m+ell] * z[0]; - for(k = 1; k < q; k++) - y[m+ell] += z[(k-1)*r+1+ell] * z[(q-k-1)*r+1+ell]; - } -} - - -/*! -Compute zero order forward mode Taylor coefficient for result of op = TanOp. - -The C++ source code corresponding to this operation is -\verbatim - z = tan(x) -\endverbatim -The auxillary result is -\verbatim - y = cos(x) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails forward_unary2_op_0 -*/ -template -inline void forward_tan_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(TanOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(TanOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; // called z in documentation - Base* y = z - cap_order; // called y in documentation - - z[0] = tan( x[0] ); - y[0] = z[0] * z[0]; -} - -/*! -Compute reverse mode partial derivatives for result of op = TanOp. - -The C++ source code corresponding to this operation is -\verbatim - z = tan(x) -\endverbatim -The auxillary result is -\verbatim - y = cos(x) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails reverse_unary2_op -*/ - -template -inline void reverse_tan_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(TanOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(TanOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to first result - const Base* z = taylor + i_z * cap_order; // called z in doc - Base* pz = partial + i_z * nc_partial; - - // Taylor coefficients and partials corresponding to auxillary result - const Base* y = z - cap_order; // called y in documentation - Base* py = pz - nc_partial; - - - size_t j = d; - size_t k; - Base base_two(2); - while(j) - { - px[j] += pz[j]; - pz[j] /= Base(j); - for(k = 1; k <= j; k++) - { px[k] += azmul(pz[j], y[j-k]) * Base(k); - py[j-k] += azmul(pz[j], x[k]) * Base(k); - } - for(k = 0; k < j; k++) - pz[k] += azmul(py[j-1], z[j-k-1]) * base_two; - - --j; - } - px[0] += azmul(pz[0], Base(1) + y[0]); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/tanh_op.hpp b/ct_core/include/ct/external/cppad/local/tanh_op.hpp deleted file mode 100644 index 1e414f1ea..000000000 --- a/ct_core/include/ct/external/cppad/local/tanh_op.hpp +++ /dev/null @@ -1,231 +0,0 @@ -// $Id: tanh_op.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_TANH_OP_HPP -# define CPPAD_TANH_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file tanh_op.hpp -Forward and reverse mode calculations for z = tanh(x). -*/ - - -/*! -Compute forward mode Taylor coefficient for result of op = TanOp. - -The C++ source code corresponding to this operation is -\verbatim - z = tanh(x) -\endverbatim -The auxillary result is -\verbatim - y = tanh(x)^2 -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op -*/ -template -inline void forward_tanh_op( - size_t p , - size_t q , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(TanOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(TanOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; - Base* y = z - cap_order; - - size_t k; - if( p == 0 ) - { z[0] = tanh( x[0] ); - y[0] = z[0] * z[0]; - p++; - } - for(size_t j = p; j <= q; j++) - { Base base_j = static_cast(j); - - z[j] = x[j]; - for(k = 1; k <= j; k++) - z[j] -= Base(k) * x[k] * y[j-k] / base_j; - - y[j] = z[0] * z[j]; - for(k = 1; k <= j; k++) - y[j] += z[k] * z[j-k]; - } -} - -/*! -Multiple directions forward mode Taylor coefficient for op = TanOp. - -The C++ source code corresponding to this operation is -\verbatim - z = tanh(x) -\endverbatim -The auxillary result is -\verbatim - y = tanh(x)^2 -\endverbatim -The value of y, and its derivatives, are computed along with the value -and derivatives of z. - -\copydetails forward_unary2_op_dir -*/ -template -inline void forward_tanh_op_dir( - size_t q , - size_t r , - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(TanOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(TanOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to argument and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + i_x * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - Base* y = z - num_taylor_per_var; - - size_t k; - size_t m = (q-1) * r + 1; - for(size_t ell = 0; ell < r; ell++) - { z[m+ell] = Base(q) * ( x[m+ell] - x[m+ell] * y[0] ); - for(k = 1; k < q; k++) - z[m+ell] -= Base(k) * x[(k-1)*r+1+ell] * y[(q-k-1)*r+1+ell]; - z[m+ell] /= Base(q); - // - y[m+ell] = Base(2) * z[m+ell] * z[0]; - for(k = 1; k < q; k++) - y[m+ell] += z[(k-1)*r+1+ell] * z[(q-k-1)*r+1+ell]; - } -} - -/*! -Compute zero order forward mode Taylor coefficient for result of op = TanOp. - -The C++ source code corresponding to this operation is -\verbatim - z = tanh(x) -\endverbatim -The auxillary result is -\verbatim - y = cos(x) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails forward_unary2_op_0 -*/ -template -inline void forward_tanh_op_0( - size_t i_z , - size_t i_x , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(TanOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(TanOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( 0 < cap_order ); - - // Taylor coefficients corresponding to argument and result - Base* x = taylor + i_x * cap_order; - Base* z = taylor + i_z * cap_order; // called z in documentation - Base* y = z - cap_order; // called y in documentation - - z[0] = tanh( x[0] ); - y[0] = z[0] * z[0]; -} - -/*! -Compute reverse mode partial derivatives for result of op = TanOp. - -The C++ source code corresponding to this operation is -\verbatim - z = tanh(x) -\endverbatim -The auxillary result is -\verbatim - y = cos(x) -\endverbatim -The value of y is computed along with the value of z. - -\copydetails reverse_unary2_op -*/ - -template -inline void reverse_tanh_op( - size_t d , - size_t i_z , - size_t i_x , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(TanOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumRes(TanOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Taylor coefficients and partials corresponding to argument - const Base* x = taylor + i_x * cap_order; - Base* px = partial + i_x * nc_partial; - - // Taylor coefficients and partials corresponding to first result - const Base* z = taylor + i_z * cap_order; // called z in doc - Base* pz = partial + i_z * nc_partial; - - // Taylor coefficients and partials corresponding to auxillary result - const Base* y = z - cap_order; // called y in documentation - Base* py = pz - nc_partial; - - - size_t j = d; - size_t k; - Base base_two(2); - while(j) - { - px[j] += pz[j]; - pz[j] /= Base(j); - for(k = 1; k <= j; k++) - { px[k] -= azmul(pz[j], y[j-k]) * Base(k); - py[j-k] -= azmul(pz[j], x[k]) * Base(k); - } - for(k = 0; k < j; k++) - pz[k] += azmul(py[j-1], z[j-k-1]) * base_two; - - --j; - } - px[0] += azmul(pz[0], Base(1) - y[0]); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/tape_link.hpp b/ct_core/include/ct/external/cppad/local/tape_link.hpp deleted file mode 100644 index 9f7f822ae..000000000 --- a/ct_core/include/ct/external/cppad/local/tape_link.hpp +++ /dev/null @@ -1,339 +0,0 @@ -// $Id: tape_link.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_TAPE_LINK_HPP -# define CPPAD_TAPE_LINK_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include -# include -# include - -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file tape_link.hpp -Routines that Link AD and ADTape Objects. - -The routines that connect the AD class to the corresponding tapes -(one for each thread). -*/ - -/*! -Handle to the tape identifier for this AD class and the specific thread. - -\tparam Base -is the base type for this AD class. - -\param thread -is the thread number. The following condition must hold -\code -(! thread_alloc::in_parallel()) || thread == thread_alloc::thread_num() -\endcode - -\return -is a handle to the tape identifier for this thread -and AD class. -*/ -template -inline tape_id_t** AD::tape_id_handle(size_t thread) -{ CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static tape_id_t* tape_id_table[CPPAD_MAX_NUM_THREADS]; - CPPAD_ASSERT_UNKNOWN( - (! thread_alloc::in_parallel()) || thread == thread_alloc::thread_num() - ); - - return tape_id_table + thread; -} - -/*! -Pointer to the tape identifier for this AD class and the specific thread. - -\tparam Base -is the base type for this AD class. - -\param thread -is the thread number; i.e., -\code -thread == thread_alloc::thread_num() -\endcode -If this condition is not satisfied, and \c NDEBUG is not defined, -a CPPAD_ASSERT_UNKNOWN is generated. - -\return -is a pointer to the tape identifier for this thread -and AD class. - -\par Restrictions -This routine should only be called if there was a tape created -for the specified thread (it may no longer be recording). -*/ -template -inline tape_id_t* AD::tape_id_ptr(size_t thread) -{ CPPAD_ASSERT_UNKNOWN( *tape_id_handle(thread) != CPPAD_NULL ) - return *tape_id_handle(thread); -} - -/*! -Handle for the tape for this AD class and the specific thread. - -\tparam Base -is the base type for this AD class. - - -\param thread -is the thread number; i.e., -\code -thread == thread_alloc::thread_num() -\endcode -If this condition is not satisfied, and \c NDEBUG is not defined, -a CPPAD_ASSERT_UNKNOWN is generated. - -\return -is a handle for the AD class and the specified thread. -*/ -template -inline ADTape** AD::tape_handle(size_t thread) -{ CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static ADTape* tape_table[CPPAD_MAX_NUM_THREADS]; - CPPAD_ASSERT_UNKNOWN( thread == thread_alloc::thread_num() ); - - return tape_table + thread; -} - -/*! -Pointer for the tape for this AD class and the current thread. - -\code -thread == thread_alloc::thread_num() -\endcode - -\tparam Base -is the base type corresponding to AD operations. - -\return -is a pointer to the tape that is currently recording AD operations -for the current thread. -If this value is \c CPPAD_NULL, there is no tape currently -recording AD operations for this thread. -*/ -template -inline ADTape* AD::tape_ptr(void) -{ size_t thread = thread_alloc::thread_num(); - return *tape_handle(thread); -} - -/*! -Pointer for the tape for this AD class and the specified tape -identifier. - -\tparam Base -is the base type corresponding to AD operations. - -\param tape_id -is the identifier for the tape that is currently recording -AD operations for the current thread. -It must hold that the current thread is -\code - thread = size_t( tape_id % CPPAD_MAX_NUM_THREADS ) -\endcode -and that there is a tape recording AD operations -for this thread. -If this is not the currently executing thread, -a variable from a different thread is being recorded on the -tape for this thread which is a user error. - -\return -is a pointer to the tape that is currently recording AD operations -for the current thread (and it is not \c CPPAD_NULL). - -\par Restrictions -This routine should only be called if there is a tape recording operaitons -for the specified thread. -*/ -template -inline ADTape* AD::tape_ptr(tape_id_t tape_id) -{ size_t thread = size_t( tape_id % CPPAD_MAX_NUM_THREADS ); - CPPAD_ASSERT_KNOWN( - thread == thread_alloc::thread_num(), - "Attempt to use an AD variable with two different threads." - ); - CPPAD_ASSERT_UNKNOWN( tape_id == *tape_id_ptr(thread) ); - CPPAD_ASSERT_UNKNOWN( *tape_handle(thread) != CPPAD_NULL ); - return *tape_handle(thread); -} - -/*! -Create and delete tapes that record AD operations for current thread. - -\par thread -the current thread is given by -\code -thread = thread_alloc::thread_num() -\endcode - -\tparam Base -is the base type corresponding to AD operations. - -\param job -This argument determines if we are creating a new tape, or deleting an -old one. -- \c tape_manage_new : -Creates and a new tape. -It is assumed that there is no tape recording AD operations -for this thread when \c tape_manage is called. -It the input value of *tape_id_handle(thread) is \c CPPAD_NULL, -it will be changed to a non-zero pointer and the corresponding value -of *tape_id_ptr(thread) will be set to -thread + CPPAD_MAX_NUM_THREADS. -- \c tape_manage_delete : -It is assumed that there is a tape recording AD operations -for this thread when \c tape_manage is called. -The value of *tape_id_ptr(thread) will be advanced by -\c CPPAD_MAX_NUM_THREADS. - - -\return -- job == tape_manage_new: a pointer to the new tape is returned. -- job == tape_manage_delete: the value \c CPPAD_NULL is returned. -*/ -template -ADTape* AD::tape_manage(tape_manage_job job) -{ // this routine has static variables so first call cannot be in parallel - CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL - - // The tape for the master thread - static ADTape tape_zero; - - // Pointer to the tape for each thread - static ADTape* tape_table[CPPAD_MAX_NUM_THREADS]; - - // The id current being used for each of the tapes - static tape_id_t tape_id_save[CPPAD_MAX_NUM_THREADS]; - - // Thread corresponding to this call - size_t thread = thread_alloc::thread_num(); - - // tape_manage_clear - if( job == tape_manage_clear ) - { // This operation cannot be done in parallel - CPPAD_ASSERT_UNKNOWN(thread == 0 && (! thread_alloc::in_parallel())); - for(thread = 0; thread < CPPAD_MAX_NUM_THREADS; thread++) - { // if this thread has a tape - if( tape_table[thread] != CPPAD_NULL ) - { // id corresponding to this thread - tape_id_save[thread] = tape_table[thread]->id_; - *tape_id_handle(thread) = &tape_id_save[thread]; - - // delete all but the master thread - if( thread != 0 ) - delete( tape_table[thread] ); - - // set the tape pointer to null - tape_table[thread] = CPPAD_NULL; - } - } - return CPPAD_NULL; - } - - // id and tape fpor this thread - tape_id_t** tape_id = tape_id_handle(thread); - ADTape** tape = tape_handle(thread); - - // check if there is no tape currently attached to this thread - if( tape_table[thread] == CPPAD_NULL ) - { // allocate separate memroy to avoid false sharing - if( thread == 0 ) - { // mastert tape is a static in this routine - tape_table[thread] = &tape_zero; - } - else - { // other tapes are allocated - tape_table[thread] = new ADTape(); - } - // current id and pointer to this tape - tape_table[thread]->id_ = tape_id_save[thread]; - *tape_id = &tape_table[thread]->id_; - - // if id is zero, initialize it so that - // thread == tape id % CPPAD_MAX_NUM_THREADS - if( **tape_id == 0 ) - **tape_id = thread + CPPAD_MAX_NUM_THREADS; - } - // make sure tape_id_handle(thread) is pointing to the proper place - CPPAD_ASSERT_UNKNOWN( *tape_id == &tape_table[thread]->id_ ); - - // make sure tape_id value is valid for this thread - CPPAD_ASSERT_UNKNOWN( - size_t( **tape_id % CPPAD_MAX_NUM_THREADS ) == thread - ); - - switch(job) - { case tape_manage_new: - // tape for this thread must be null at the start - CPPAD_ASSERT_UNKNOWN( *tape == CPPAD_NULL ); - *tape = tape_table[thread]; - break; - - case tape_manage_delete: - CPPAD_ASSERT_UNKNOWN( *tape == tape_table[thread] ); - CPPAD_ASSERT_KNOWN( - std::numeric_limits::max() - - CPPAD_MAX_NUM_THREADS > **tape_id, - "To many different tapes given the type used for " - "CPPAD_TAPE_ID_TYPE" - ); - // advance tape identfier so all AD variables become parameters - **tape_id += CPPAD_MAX_NUM_THREADS; - // free memory corresponding to recording in the old tape - tape_table[thread]->Rec_.free(); - // inform rest of CppAD that no tape recording for this thread - *tape = CPPAD_NULL; - break; - - case tape_manage_clear: - CPPAD_ASSERT_UNKNOWN(false); - } - return *tape; -} - -/*! -Get a pointer to tape that records AD operations for the current thread. - -\tparam Base -is the base type corresponding to AD operations. - -\par thread -The current thread must be given by -\code - thread = this->tape_id_ % CPPAD_MAX_NUM_THREADS -\endcode - -\return -is a pointer to the tape that is currently recording AD operations -for the current thread. -This value must not be \c CPPAD_NULL; i.e., there must be a tape currently -recording AD operations for this thread. -*/ - -template -inline ADTape *AD::tape_this(void) const -{ - size_t thread = size_t( tape_id_ % CPPAD_MAX_NUM_THREADS ); - CPPAD_ASSERT_UNKNOWN( tape_id_ == *tape_id_ptr(thread) ); - CPPAD_ASSERT_UNKNOWN( *tape_handle(thread) != CPPAD_NULL ); - return *tape_handle(thread); -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/test_vector.hpp b/ct_core/include/ct/external/cppad/local/test_vector.hpp deleted file mode 100644 index 3e4cffc54..000000000 --- a/ct_core/include/ct/external/cppad/local/test_vector.hpp +++ /dev/null @@ -1,136 +0,0 @@ -// $Id: test_vector.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_TEST_VECTOR_HPP -# define CPPAD_TEST_VECTOR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin test_vector$$ -$spell - ifdef - undef - Microsofts - CppADvector - hpp - std - endif - ublas - Dir - valarray - stdvector -$$ - - -$section Choosing The Vector Testing Template Class$$ -$mindex CPPAD_TEST_VECTOR test$$ - -$head Deprecated 2012-07-03$$ -The $code CPPAD_TEST_VECTOR$$ macro has been deprecated, -use $cref/CPPAD_TESTVECTOR/testvector/$$ instead. - -$head Syntax$$ -$codei%CPPAD_TEST_VECTOR<%Scalar%> -%$$ - -$head Introduction$$ -Many of the CppAD $cref/examples/example/$$ and tests use -the $code CPPAD_TEST_VECTOR$$ template class to pass information. -The default definition for this template class is -$cref/CppAD::vector/CppAD_vector/$$. - -$head MS Windows$$ -The include path for boost is not defined in the Windows project files. -If we are using Microsofts compiler, the following code overrides the setting -of $code CPPAD_BOOSTVECTOR$$: -$codep */ -// The next 7 lines are C++ source code. -# ifdef _MSC_VER -# if CPPAD_BOOSTVECTOR -# undef CPPAD_BOOSTVECTOR -# define CPPAD_BOOSTVECTOR 0 -# undef CPPAD_CPPADVECTOR -# define CPPAD_CPPADVECTOR 1 -# endif -# endif -/* $$ - -$head CppAD::vector$$ -By default $code CPPAD_CPPADVECTOR$$ is true -and $code CPPAD_TEST_VECTOR$$ is defined by the following source code -$codep */ -// The next 3 line are C++ source code. -# if CPPAD_CPPADVECTOR -# define CPPAD_TEST_VECTOR CppAD::vector -# endif -/* $$ -If you specify $code --with-eigenvector$$ on the -$cref/configure/auto_tools/Configure/$$ command line, -$code CPPAD_EIGENVECTOR$$ is true. -This vector type cannot be supported by $code CPPAD_TEST_VECTOR$$ -(use $cref/CPPAD_TESTVECTOR/testvector/$$ for this support) -so $code CppAD::vector$$ is used in this case -$codep */ -// The next 3 line are C++ source code. -# if CPPAD_EIGENVECTOR -# define CPPAD_TEST_VECTOR CppAD::vector -# endif -/* $$ - - -$head std::vector$$ -If you specify $code --with-stdvector$$ on the -$cref/configure/auto_tools/Configure/$$ -command line during CppAD installation, -$code CPPAD_STDVECTOR$$ is true -and $code CPPAD_TEST_VECTOR$$ is defined by the following source code -$codep */ -// The next 4 lines are C++ source code. -# if CPPAD_STDVECTOR -# include -# define CPPAD_TEST_VECTOR std::vector -# endif -/* $$ -In this case CppAD will use $code std::vector$$ for its examples and tests. -Use of $code CppAD::vector$$, $code std::vector$$, -and $code std::valarray$$ with CppAD is always tested to some degree. -Specifying $code --with-stdvector$$ will increase the amount of -$code std::vector$$ testing. - -$head boost::numeric::ublas::vector$$ -If you specify a value for $icode boost_dir$$ on the configure -command line during CppAD installation, -$code CPPAD_BOOSTVECTOR$$ is true -and $code CPPAD_TEST_VECTOR$$ is defined by the following source code -$codep */ -// The next 4 lines are C++ source code. -# if CPPAD_BOOSTVECTOR -# include -# define CPPAD_TEST_VECTOR boost::numeric::ublas::vector -# endif -/* $$ -In this case CppAD will use Ublas vectors for its examples and tests. -Use of $code CppAD::vector$$, $code std::vector$$, -and $code std::valarray$$ with CppAD is always tested to some degree. -Specifying $icode boost_dir$$ will increase the amount of -Ublas vector testing. - -$head CppADvector Deprecated 2007-07-28$$ -The preprocessor symbol $code CppADvector$$ is defined to -have the same value as $code CPPAD_TEST_VECTOR$$ but its use is deprecated: -$codep */ -# define CppADvector CPPAD_TEST_VECTOR -/* $$ -$end ------------------------------------------------------------------------- -*/ - -# endif diff --git a/ct_core/include/ct/external/cppad/local/testvector.hpp b/ct_core/include/ct/external/cppad/local/testvector.hpp deleted file mode 100644 index 8cb2be74f..000000000 --- a/ct_core/include/ct/external/cppad/local/testvector.hpp +++ /dev/null @@ -1,113 +0,0 @@ -// $Id: testvector.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_TESTVECTOR_HPP -# define CPPAD_TESTVECTOR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin testvector$$ -$spell - CppAD - cmake - testvector - cppad - Eigen - ifdef - hpp - std - endif - ublas -$$ - - -$section Using The CppAD Test Vector Template Class$$ -$mindex CPPAD_TESTVECTOR$$ - -$head Syntax$$ -$codei%CPPAD_TESTVECTOR(%Scalar%) -%$$ - -$head Introduction$$ -Many of the CppAD $cref/examples/example/$$ and tests use -the $code CPPAD_TESTVECTOR$$ template class to pass information to CppAD. -This is not a true template class because it's syntax uses -$codei%(%Scalar%)%$$ instead of $codei%<%Scalar%>%$$. -This enables us to use -$codei% - Eigen::Matrix<%Scalar%, Eigen::Dynamic, 1> -%$$ -as one of the possible cases for this 'template class'. - -$head CppAD::vector$$ -If in the $cref/cmake command/cmake/CMake Command/$$ -you specify $cref cppad_testvector$$ to be $code cppad$$, -$code CPPAD_CPPADVECTOR$$ will be true. -In this case, -$code CPPAD_TESTVECTOR$$ is defined by the following source code: -$codep */ -# if CPPAD_CPPADVECTOR -# define CPPAD_TESTVECTOR(Scalar) CppAD::vector< Scalar > -# endif -/* $$ -In this case CppAD will use its own vector for -many of its examples and tests. - -$head std::vector$$ -If in the cmake command -you specify $icode cppad_testvector$$ to be $code std$$, -$code CPPAD_STDVECTOR$$ will be true. -In this case, -$code CPPAD_TESTVECTOR$$ is defined by the following source code: -$codep */ -# if CPPAD_STDVECTOR -# include -# define CPPAD_TESTVECTOR(Scalar) std::vector< Scalar > -# endif -/* $$ -In this case CppAD will use standard vector for -many of its examples and tests. - -$head boost::numeric::ublas::vector$$ -If in the cmake command -you specify $icode cppad_testvector$$ to be $code boost$$, -$code CPPAD_BOOSTVECTOR$$ will be true. -In this case, -$code CPPAD_TESTVECTOR$$ is defined by the following source code: -$codep */ -# if CPPAD_BOOSTVECTOR -# include -# define CPPAD_TESTVECTOR(Scalar) boost::numeric::ublas::vector< Scalar > -# endif -/* $$ -In this case CppAD will use this boost vector for -many of its examples and tests. - -$head Eigen Vectors$$ -If in the cmake command -you specify $icode cppad_testvector$$ to be $code eigen$$, -$code CPPAD_EIGENVECTOR$$ will be true. -In this case, -$code CPPAD_TESTVECTOR$$ is defined by the following source code: -$codep */ -# if CPPAD_EIGENVECTOR -# include -# define CPPAD_TESTVECTOR(Scalar) Eigen::Matrix< Scalar , Eigen::Dynamic, 1> -# endif -/* $$ -In this case CppAD will use the Eigen vector -for many of its examples and tests. - -$end ------------------------------------------------------------------------- -*/ - -# endif diff --git a/ct_core/include/ct/external/cppad/local/unary_minus.hpp b/ct_core/include/ct/external/cppad/local/unary_minus.hpp deleted file mode 100644 index f745ac2bc..000000000 --- a/ct_core/include/ct/external/cppad/local/unary_minus.hpp +++ /dev/null @@ -1,104 +0,0 @@ -// $Id: unary_minus.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_UNARY_MINUS_HPP -# define CPPAD_UNARY_MINUS_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin UnaryMinus$$ -$spell - Vec - const - inline -$$ - - -$section AD Unary Minus Operator$$ -$mindex -$$ - -$head Syntax$$ - -$icode%y% = - %x%$$ - - -$head Purpose$$ -Computes the negative of $icode x$$. - -$head Base$$ -The operation in the syntax above must be supported for the case where -the operand is a $code const$$ $icode Base$$ object. - -$head x$$ -The operand $icode x$$ has one of the following prototypes -$codei% - const AD<%Base%> &%x% - const VecAD<%Base%>::reference &%x% -%$$ - -$head y$$ -The result $icode y$$ has type -$codei% - AD<%Base%> %y% -%$$ -It is equal to the negative of the operand $icode x$$. - -$head Operation Sequence$$ -This is an AD of $icode Base$$ -$cref/atomic operation/glossary/Operation/Atomic/$$ -and hence is part of the current -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Derivative$$ -If $latex f$$ is a -$cref/Base function/glossary/Base Function/$$, -$latex \[ - \D{[ - f(x) ]}{x} = - \D{f(x)}{x} -\] $$ - -$head Example$$ -$children% - example/unary_minus.cpp -%$$ -The file -$cref unary_minus.cpp$$ -contains an example and test of this operation. - -$end -------------------------------------------------------------------------------- -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -// Broken g++ compiler inhibits declaring unary minus a member or friend -template -inline AD AD::operator - (void) const -{ // should make a more efficient version by adding unary minus to - // Operator.h (some day) - AD result(0); - - result -= *this; - - return result; -} - - -template -inline AD operator - (const VecAD_reference &right) -{ return - right.ADBase(); } - -} -// END CppAD namespace - - -# endif diff --git a/ct_core/include/ct/external/cppad/local/unary_plus.hpp b/ct_core/include/ct/external/cppad/local/unary_plus.hpp deleted file mode 100644 index c09e1e28e..000000000 --- a/ct_core/include/ct/external/cppad/local/unary_plus.hpp +++ /dev/null @@ -1,99 +0,0 @@ -// $Id: unary_plus.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_UNARY_PLUS_HPP -# define CPPAD_UNARY_PLUS_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin UnaryPlus$$ -$spell - Vec - const - inline -$$ - - -$section AD Unary Plus Operator$$ -$mindex +$$ - -$head Syntax$$ - -$icode%y% = + %x%$$ - - -$head Purpose$$ -Performs the unary plus operation -(the result $icode y$$ is equal to the operand $icode x$$). - - -$head x$$ -The operand $icode x$$ has one of the following prototypes -$codei% - const AD<%Base%> &%x% - const VecAD<%Base%>::reference &%x% -%$$ - -$head y$$ -The result $icode y$$ has type -$codei% - AD<%Base%> %y% -%$$ -It is equal to the operand $icode x$$. - -$head Operation Sequence$$ -This is an AD of $icode Base$$ -$cref/atomic operation/glossary/Operation/Atomic/$$ -and hence is part of the current -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Derivative$$ -If $latex f$$ is a -$cref/Base function/glossary/Base Function/$$, -$latex \[ - \D{[ + f(x) ]}{x} = \D{f(x)}{x} -\] $$ - - - -$head Example$$ -$children% - example/unary_plus.cpp -%$$ -The file -$cref unary_plus.cpp$$ -contains an example and test of this operation. - -$end -------------------------------------------------------------------------------- -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -inline AD AD::operator + (void) const -{ AD result(*this); - - return result; -} - - -template -inline AD operator + (const VecAD_reference &right) -{ return right.ADBase(); } - -} -// END CppAD namespace - - -# endif diff --git a/ct_core/include/ct/external/cppad/local/undef.hpp b/ct_core/include/ct/external/cppad/local/undef.hpp deleted file mode 100644 index d684e8221..000000000 --- a/ct_core/include/ct/external/cppad/local/undef.hpp +++ /dev/null @@ -1,98 +0,0 @@ -// $Id: undef.hpp 3768 2015-12-28 18:58:35Z bradbell $ -# ifndef CPPAD_UNDEF_HPP -# define CPPAD_UNDEF_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ----------------------------------------------------------------------------- -Preprecessor definitions that presist after cppad/cppad.hpp is included: - -# undef CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL used by CPPAD_USER_ATOMIC -# undef CPPAD_ASSERT_KNOWN needed by cppad_ipopt -# undef CPPAD_ASSERT_UNKNOWN needed by cppad_ipopt -# undef CPPAD_HASH_TABLE_SIZE used by test_more/optimize.cpp -# undef EIGEN_MATRIXBASE_PLUGIN example use of Eigen with CppAD - -# undef CPPAD_BOOL_BINARY in user api -# undef CPPAD_BOOL_UNARY in user api -# undef CPPAD_DISCRETE_FUNCTION in user api -# undef CPPAD_EIGENVECTOR in user api -# undef CPPAD_INTERNAL_SPARSE_SET in user api -# undef CPPAD_MAX_NUM_THREADS in user api -# undef CPPAD_NUMERIC_LIMITS in user api -# undef CPPAD_NULL in user api -# undef CPPAD_PACKAGE_STRING in user api -# undef CPPAD_STANDARD_MATH_UNARY in user api -# undef CPPAD_TAPE_ADDR_TYPE in user api -# undef CPPAD_TAPE_ID_TYPE in user api -# undef CPPAD_TESTVECTOR in user api -# undef CPPAD_TO_STRING in user api -# undef CPPAD_USE_CPLUSPLUS_2011 in user api - -# undef CPPAD_TRACK_COUNT in deprecated api -# undef CPPAD_TRACK_DEL_VEC in deprecated api -# undef CPPAD_TRACK_EXTEND in deprecated api -# undef CPPAD_TRACK_NEW_VEC in deprecated api -# undef CPPAD_USER_ATOMIC in deprecated api - -# undef CPPAD_TEST_VECTOR deprecated verssion of CPPAD_TESTVECTOR -# undef CppADCreateBinaryBool deprecated version of CPPAD_BOOL_BINARY -# undef CppADCreateDiscrete deprecated version of CPPAD_DISCRETE_FUNCTION -# undef CppADCreateUnaryBool deprecated version of CPPAD_BOOL_UNARY -# undef CppADTrackCount deprecated version of CPPAD_TRACK_COUNT -# undef CppADTrackDelVec deprecated version of CPPAD_TRACK_DEL_VEC -# undef CppADTrackExtend deprecated version of CPPAD_TRACK_EXTEND -# undef CppADTrackNewVec deprecated version of CPPAD_TRACK_NEW_VEC -# undef CppADvector deprecated version of CPPAD_TEST_VECTOR - -// for conditional testing when implicit conversion is not present -# undef CPPAD_DEPRECATED ------------------------------------------------------------------------------ -*/ -// Preprecessor definitions that do not presist -# undef CPPAD_ASSERT_NARG_NRES -# undef CPPAD_ASSERT_ARG_BEFORE_RESULT -# undef CPPAD_AZMUL -# undef CPPAD_BOOSTVECTOR -# undef CPPAD_COND_EXP -# undef CPPAD_COND_EXP_BASE_REL -# undef CPPAD_COND_EXP_REL -# undef CPPAD_CPPADVECTOR -# undef CPPAD_FOLD_AD_VALUED_BINARY_OPERATOR -# undef CPPAD_FOLD_ASSIGNMENT_OPERATOR -# undef CPPAD_FOLD_BOOL_VALUED_BINARY_OPERATOR -# undef CPPAD_FOR_JAC_SWEEP_TRACE -# undef CPPAD_HAS_COLPACK -# undef CPPAD_HAS_GETTIMEOFDAY -# undef CPPAD_HAS_MKSTEMP -# undef CPPAD_HAS_TMPNAM_S -# undef CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -# undef CPPAD_LIB_EXPORT -# undef CPPAD_MAX_NUM_CAPACITY -# undef CPPAD_MIN_DOUBLE_CAPACITY -# undef CPPAD_OP_CODE_TYPE -# undef CPPAD_REVERSE_SWEEP_TRACE -# undef CPPAD_REV_HES_SWEEP_TRACE -# undef CPPAD_REV_JAC_SWEEP_TRACE -# undef CPPAD_SIZE_T_NOT_UNSIGNED_INT -# undef CPPAD_STANDARD_MATH_UNARY_AD -# undef CPPAD_STDVECTOR -# undef CPPAD_TRACE_CAPACITY -# undef CPPAD_TRACE_THREAD -# undef CPPAD_TRACK_DEBUG -# undef CPPAD_USER_MACRO -# undef CPPAD_USER_MACRO_ONE -# undef CPPAD_USER_MACRO_TWO -# undef CPPAD_VEC_AD_COMPUTED_ASSIGNMENT - -# endif diff --git a/ct_core/include/ct/external/cppad/local/user_ad.hpp b/ct_core/include/ct/external/cppad/local/user_ad.hpp deleted file mode 100644 index 0f5e2ba84..000000000 --- a/ct_core/include/ct/external/cppad/local/user_ad.hpp +++ /dev/null @@ -1,73 +0,0 @@ -// $Id: user_ad.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_USER_AD_HPP -# define CPPAD_USER_AD_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* ---------------------------------------------------------------------------- - -$begin AD$$ -$spell - std - bool - cos - Cpp -$$ - -$section AD Objects$$ -$mindex require$$ - - -$head Purpose$$ -The sections listed below describe the operations -that are available to $cref/AD of Base/glossary/AD of Base/$$ objects. -These objects are used to $cref/tape/glossary/Tape/$$ -an AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. -This operation sequence can -be transferred to an $cref ADFun$$ object where it -can be used to evaluate the corresponding -function and derivative values. - -$head Base Type Requirements$$ -The $icode Base$$ requirements are provided by the CppAD package -for the following base types: -$code float$$, -$code double$$, -$code std::complex$$, -$code std::complex$$. -Otherwise, see $cref base_require$$. - - -$childtable% - cppad/local/ad_ctor.hpp% - cppad/local/ad_assign.hpp% - cppad/local/convert.hpp% - cppad/local/ad_valued.hpp% - cppad/local/bool_valued.hpp% - cppad/local/vec_ad.hpp% - cppad/base_require.hpp -%$$ - -$end ---------------------------------------------------------------------------- -*/ - -# include -# include -# include -# include -# include -# include -# include - -# endif diff --git a/ct_core/include/ct/external/cppad/local/user_state.hpp b/ct_core/include/ct/external/cppad/local/user_state.hpp deleted file mode 100644 index e1900f95a..000000000 --- a/ct_core/include/ct/external/cppad/local/user_state.hpp +++ /dev/null @@ -1,32 +0,0 @@ -// $Id$ -# ifndef CPPAD_LOCAL_USER_STATE_HPP -# define CPPAD_LOCAL_USER_STATE_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { namespace local { // BEGIN_CPPAD_LOCAL_NAMESPACE - -enum enum_user_state { - /// next UserOp marks beginning of a user atomic call - start_user, - - /// next UsrapOp (UsravOp) is a parameter (variable) argument - arg_user, - - /// next UsrrpOp (UsrrvOp) is a parameter (variable) result - ret_user, - - /// next UserOp marks end of a user atomic call - end_user -}; - -} } // END_CPPAD_LOCAL_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/local/value.hpp b/ct_core/include/ct/external/cppad/local/value.hpp deleted file mode 100644 index 294aeb399..000000000 --- a/ct_core/include/ct/external/cppad/local/value.hpp +++ /dev/null @@ -1,101 +0,0 @@ -// $Id: value.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_VALUE_HPP -# define CPPAD_VALUE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Value$$ -$spell - const -$$ - - - -$section Convert From an AD Type to its Base Type$$ -$mindex Value$$ - -$head Syntax$$ -$icode%b% = Value(%x%)%$$ - -$head See Also$$ -$cref var2par$$ - - -$head Purpose$$ -Converts from an AD type to the corresponding -$cref/base type/glossary/Base Type/$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const AD<%Base%> &%x% -%$$ - -$head b$$ -The return value $icode b$$ has prototype -$codei% - %Base% %b% -%$$ - -$head Operation Sequence$$ -The result of this operation is not an -$cref/AD of Base/glossary/AD of Base/$$ object. -Thus it will not be recorded as part of an -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$. - -$head Restriction$$ -If the argument $icode x$$ is a -$cref/variable/glossary/Variable/$$ its dependency information -would not be included in the $code Value$$ result (see above). -For this reason, -the argument $icode x$$ must be a $cref/parameter/glossary/Parameter/$$; i.e., -it cannot depend on the current -$cref/independent variables/glossary/Tape/Independent Variable/$$. - -$head Example$$ -$children% - example/value.cpp -%$$ -The file -$cref value.cpp$$ -contains an example and test of this operation. - -$end -------------------------------------------------------------------------------- -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -Base Value(const AD &x) -{ Base result; - - CPPAD_ASSERT_KNOWN( - Parameter(x) , - "Value: argument is a variable (not a parameter)" - ); - - - result = x.value_; - - return result; -} - -} -// END CppAD namespace - - -# endif diff --git a/ct_core/include/ct/external/cppad/local/var2par.hpp b/ct_core/include/ct/external/cppad/local/var2par.hpp deleted file mode 100644 index f9fa4fae0..000000000 --- a/ct_core/include/ct/external/cppad/local/var2par.hpp +++ /dev/null @@ -1,92 +0,0 @@ -// $Id: var2par.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_VAR2PAR_HPP -# define CPPAD_VAR2PAR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* ------------------------------------------------------------------------------- - -$begin Var2Par$$ -$spell - var - const -$$ - - -$section Convert an AD Variable to a Parameter$$ -$mindex Var2Par from value_ obtain during taping$$ - -$head Syntax$$ -$icode%y% = Var2Par(%x%)%$$ - -$head See Also$$ -$cref value$$ - - -$head Purpose$$ -Returns a -$cref/parameter/glossary/Parameter/$$ $icode y$$ -with the same value as the -$cref/variable/glossary/Variable/$$ $icode x$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const AD<%Base%> &x -%$$ -The argument $icode x$$ may be a variable or parameter. - - -$head y$$ -The result $icode y$$ has prototype -$codei% - AD<%Base%> &y -%$$ -The return value $icode y$$ will be a parameter. - - -$head Example$$ -$children% - example/var2par.cpp -%$$ -The file -$cref var2par.cpp$$ -contains an example and test of this operation. -It returns true if it succeeds and false otherwise. - -$end ------------------------------------------------------------------------------- -*/ - -// BEGIN CppAD namespace -namespace CppAD { - -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -AD Var2Par(const AD &x) -{ AD y(x.value_); - return y; -} - - -template -CPPAD_INLINE_FRIEND_TEMPLATE_FUNCTION -AD Var2Par(const VecAD_reference &x) -{ AD y(x.ADBase()); - y.id_ = 0; -} - - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/local/vec_ad.hpp b/ct_core/include/ct/external/cppad/local/vec_ad.hpp deleted file mode 100644 index ec3524feb..000000000 --- a/ct_core/include/ct/external/cppad/local/vec_ad.hpp +++ /dev/null @@ -1,742 +0,0 @@ -// $Id: vec_ad.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_VEC_AD_HPP -# define CPPAD_VEC_AD_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin VecAD$$ -$spell - cppad.hpp - CondExpGt - grep - Ld - vp - Lu - wc - op - Ldp - Ldv - Taylor - VecAD - const - Cpp -$$ - - -$section AD Vectors that Record Index Operations$$ -$mindex VecAD tape reference VecAD$$ - - -$head Syntax$$ -$codei%VecAD<%Base%> %v%(%n%)%$$ -$pre -$$ -$icode%v%.size()%$$ -$pre -$$ -$icode%b% = %v%[%i%]%$$ -$pre -$$ -$icode%r% = %v%[%x%]%$$ - -$head Purpose$$ -If either $icode v$$ or $icode x$$ is a -$cref/variable/glossary/Variable/$$, -the indexing operation -$codei% - %r% = %v%[%x%] -%$$ -is recorded in the corresponding -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$ and -transferred to the corresponding $cref ADFun$$ object $icode f$$. -Such an index can change each time -zero order $cref/f.Forward/Forward/$$ is used; i.e., -$icode f$$ is evaluated with new value for the -$cref/independent variables/glossary/Tape/Independent Variable/$$. -Note that the value of $icode y$$ depends on the value of $icode x$$ -in a discrete fashion and CppAD computes its partial derivative with -respect to $icode x$$ as zero. - -$head Alternatives$$ -If only the values in the vector, -and not the indices, -depend on the independent variables, -the class $icode%Vector%< AD<%Base%> >%$$ is much more efficient for -storing AD values where $icode Vector$$ is any -$cref SimpleVector$$ template class, -If only the indices, -and not the values in the vector, -depend on the independent variables, -The $cref Discrete$$ functions are a much more efficient -way to represent these vectors. - -$head VecAD::reference$$ -The result $icode r$$ has type -$codei% - VecAD<%Base%>::reference -%$$ -which is very much like the $codei%AD<%Base%>%$$ type -with some notable exceptions: - -$subhead Exceptions$$ -$list number$$ -The object $icode r$$ cannot be used with the -$cref Value$$ function to compute the corresponding $icode Base$$ value. -If $icode v$$ and $icode i$$ are not $cref/variables/glossary/Variable/$$ -$codei% - %b% = v[%i%] -%$$ -can be used to compute the corresponding $icode Base$$ value. - -$lnext -The object $icode r$$ cannot be used -with the $cref/computed assignments operators/Arithmetic/$$ -$code +=$$, -$code -=$$, -$code *=$$, or -$code /=$$. -For example, the following syntax is not valid: -$codei% - %v%[%x%] += %z%; -%$$ -no matter what the types of $icode z$$. - -$lnext -Assignment to $icode r$$ returns a $code void$$. -For example, the following syntax is not valid: -$codei% - %z% = %v%[%x%] = %u%; -%$$ -no matter what the types of $icode z$$, and $icode u$$. - -$lnext -The $cref CondExp$$ functions do not accept -$codei%VecAD<%Base%>::reference%$$ arguments. -For example, the following syntax is not valid: -$codei% - CondExpGt(%v%[%x%], %z%, %u%, %v%) -%$$ -no matter what the types of $icode z$$, $icode u$$, and $icode v$$. - -$lnext -The $cref/Parameter and Variable/ParVar/$$ functions cannot be used with -$codei%VecAD<%Base%>::reference%$$ arguments like $icode r$$, -use the entire $codei%VecAD<%Base%>%$$ vector instead; i.e. $icode v$$. - -$lnext -The vectors passed to $cref Independent$$ must have elements -of type $codei%AD<%Base%>%$$; i.e., $cref VecAD$$ vectors -cannot be passed to $code Independent$$. - -$lnext -If one uses this type in a -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$, -$cref/sparsity pattern/glossary/Sparsity Pattern/$$ calculations -($cref Sparse$$) -are less efficient because the dependence of different -elements of the vector cannot be separated. - -$lend - -$head Constructor$$ - -$subhead v$$ -The syntax -$codei% - VecAD<%Base%> %v%(%n%) -%$$ -creates an $code VecAD$$ object $icode v$$ with -$icode n$$ elements. -The initial value of the elements of $icode v$$ is unspecified. - -$head n$$ -The argument $icode n$$ has prototype -$codei% - size_t %n% -%$$ - -$head size$$ -The syntax -$codei% - %v%.size() -%$$ -returns the number of elements in the vector $icode v$$; -i.e., the value of $icode n$$ when it was constructed. - -$head size_t Indexing$$ -We refer to the syntax -$codei% - %b% = %v%[%i%] -%$$ -as $code size_t$$ indexing of a $code VecAD$$ object. -This indexing is only valid if the vector $icode v$$ is a -$cref/parameter/ParVar/$$; i.e., -it does not depend on the independent variables. - -$subhead i$$ -The operand $icode i$$ has prototype -$codei% - size_t %i% -%$$ -It must be greater than or equal zero -and less than $icode n$$; i.e., less than -the number of elements in $icode v$$. - -$subhead b$$ -The result $icode b$$ has prototype -$codei% - %Base% %b% -%$$ -and is a reference to the $th i$$ element in the vector $icode v$$. -It can be used to change the element value; -for example, -$codei% - %v%[%i%] = %c% -%$$ -is valid where $icode c$$ is a $icode Base$$ object. -The reference $icode b$$ is no longer valid once the -destructor for $icode v$$ is called; for example, -when $icode v$$ falls out of scope. - -$head AD Indexing$$ -We refer to the syntax -$codei% - %r% = %v%[%x%] -%$$ -as AD indexing of a $code VecAD$$ object. - -$subhead x$$ -The argument $icode x$$ has prototype -$codei% - const AD<%Base%> &%x% -%$$ -The value of $icode x$$ must be greater than or equal zero -and less than $icode n$$; i.e., less than -the number of elements in $icode v$$. - -$subhead r$$ -The result $icode r$$ has prototype -$codei% - VecAD<%Base%>::reference %r% -%$$ -The object $icode r$$ has an AD type and its -operations are recorded as part of the same -AD of $icode Base$$ -$cref/operation sequence/glossary/Operation/Sequence/$$ as -for $codei%AD<%Base%>%$$ objects. -It acts as a reference to the -element with index $latex {\rm floor} (x)$$ in the vector $icode v$$ -($latex {\rm floor} (x)$$ is -the greatest integer less than or equal $icode x$$). -Because it is a reference, it can be used to change the element value; -for example, -$codei% - %v%[%x%] = %z% -%$$ -is valid where $icode z$$ is an -$codei%VecAD<%Base%>::reference%$$ object. -As a reference, $icode r$$ is no longer valid once the -destructor for $icode v$$ is called; for example, -when $icode v$$ falls out of scope. - -$head Example$$ -$children% - example/vec_ad.cpp -%$$ -The file -$cref vec_ad.cpp$$ -contains an example and test using $code VecAD$$ vectors. -It returns true if it succeeds and false otherwise. - - -$head Speed and Memory$$ -The $cref VecAD$$ vector type is inefficient because every -time an element of a vector is accessed, a new CppAD -$cref/variable/glossary/Variable/$$ is created on the tape -using either the $code Ldp$$ or $code Ldv$$ operation -(unless all of the elements of the vector are -$cref/parameters/glossary/Parameter/$$). -The effect of this can be seen by executing the following steps: - -$list number$$ -In the file $code cppad/local/forward1sweep.h$$, -change the definition of $code CPPAD_FORWARD1SWEEP_TRACE$$ to -$codep - # define CPPAD_FORWARD1SWEEP_TRACE 1 -$$ -$lnext -In the $code Example$$ directory, execute the command -$codep - ./test_one.sh lu_vec_ad_ok.cpp lu_vec_ad.cpp -DNDEBUG > lu_vec_ad_ok.log -$$ -This will write a trace of all the forward tape operations, -for the test case $cref lu_vec_ad_ok.cpp$$, -to the file $code lu_vec_ad_ok.log$$. -$lnext -In the $code Example$$ directory execute the commands -$codep - grep "op=" lu_vec_ad_ok.log | wc -l - grep "op=Ld[vp]" lu_vec_ad_ok.log | wc -l - grep "op=St[vp][vp]" lu_vec_ad_ok.log | wc -l -$$ -The first command counts the number of operators in the tracing, -the second counts the number of VecAD load operations, -and the third counts the number of VecAD store operations. -(For CppAD version 05-11-20 these counts were 956, 348, and 118 -respectively.) -$lend - -$end ------------------------------------------------------------------------- -*/ -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file vec_ad.hpp -Defines the VecAD class. -*/ - -/*! -\def CPPAD_VEC_AD_COMPUTED_ASSIGNMENT(op, name) -Prints an error message if the correspinding computed assignment is used. - -THis macro is used to print an error message if any of the -computed assignments are used with the VecAD_reference class. -The argument \c op is one of the following: -+= , -= , *= , /=. -The argument \c name, is a string literal with the name of the -computed assignment \c op. -*/ -# define CPPAD_VEC_AD_COMPUTED_ASSIGNMENT(op, name) \ -VecAD_reference& operator op (const VecAD_reference &right) \ -{ CPPAD_ASSERT_KNOWN( \ - false, \ - "Cannot use a ADVec element on left side of" name \ - ); \ - return *this; \ -} \ -VecAD_reference& operator op (const AD &right) \ -{ CPPAD_ASSERT_KNOWN( \ - false, \ - "Cannot use a ADVec element on left side of" name \ - ); \ - return *this; \ -} \ -VecAD_reference& operator op (const Base &right) \ -{ CPPAD_ASSERT_KNOWN( \ - false, \ - "Cannot use a ADVec element on left side of" name \ - ); \ - return *this; \ -} - -/*! -Class used to hold a reference to an element of a VecAD object. - -\tparam Base -Elements of this class act like an AD (in a restricted sense), -in addition they track (on the tape) the index they correspond to. -*/ -template -class VecAD_reference { - friend bool Parameter (const VecAD &vec); - friend bool Variable (const VecAD &vec); - friend class VecAD; - friend class ADTape; - -private: - /// pointer to vecad vector that this is a element of - VecAD *vec_; - /// index in vecad vector that this element corresponds to - AD ind_; // index for this element -public: - /*! - consructor - - \param vec - value of vec_ - - \param ind - value of ind_ - */ - VecAD_reference(VecAD *vec, const AD& ind) - : vec_( vec ) , ind_(ind) - { } - - // assignment operators - inline void operator = (const VecAD_reference &right); - void operator = (const AD &right); - void operator = (const Base &right); - void operator = (int right); - - // computed assignments - CPPAD_VEC_AD_COMPUTED_ASSIGNMENT( += , " += " ) - CPPAD_VEC_AD_COMPUTED_ASSIGNMENT( -= , " -= " ) - CPPAD_VEC_AD_COMPUTED_ASSIGNMENT( *= , " *= " ) - CPPAD_VEC_AD_COMPUTED_ASSIGNMENT( /= , " /= " ) - - - /// Conversion from VecAD_reference to AD. - /// puts the correspond vecad load instruction in the tape. - AD ADBase(void) const - { AD result; - - size_t i = static_cast( Integer(ind_) ); - CPPAD_ASSERT_UNKNOWN( i < vec_->length_ ); - - // AD value corresponding to this element - result.value_ = vec_->data_[i]; - - // this address will be recorded in tape and must be - // zero for parameters - CPPAD_ASSERT_UNKNOWN( Parameter(result) ); - result.taddr_ = 0; - - // index corresponding to this element - if( Variable(*vec_) ) - { - ADTape* tape = AD::tape_ptr(vec_->tape_id_); - CPPAD_ASSERT_UNKNOWN( tape != CPPAD_NULL ); - CPPAD_ASSERT_UNKNOWN( vec_->offset_ > 0 ); - - size_t load_op_index = tape->Rec_.num_load_op_rec(); - if( IdenticalPar(ind_) ) - { CPPAD_ASSERT_UNKNOWN( NumRes(LdpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(LdpOp) == 3 ); - - // put operand addresses in tape - tape->Rec_.PutArg( - vec_->offset_, i, load_op_index - ); - // put operator in the tape, ind_ is a parameter - result.taddr_ = tape->Rec_.PutLoadOp(LdpOp); - // change result to variable for this load - result.tape_id_ = tape->id_; - } - else - { CPPAD_ASSERT_UNKNOWN( NumRes(LdvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( NumArg(LdvOp) == 3 ); - addr_t ind_taddr; - if( Parameter(ind_) ) - { // kludge that should not be needed - // if ind_ instead of i is used for index - // in the tape - ind_taddr = tape->RecordParOp( - ind_.value_ - ); - } - else ind_taddr = ind_.taddr_; - CPPAD_ASSERT_UNKNOWN( ind_taddr > 0 ); - - // put operand addresses in tape - // (value of third arugment does not matter) - tape->Rec_.PutArg( - vec_->offset_, ind_taddr, load_op_index - ); - // put operator in the tape, ind_ is a variable - result.taddr_ = tape->Rec_.PutLoadOp(LdvOp); - // change result to variable for this load - result.tape_id_ = tape->id_; - } - } - return result; - } -}; - -/*! -Vector of AD objects that tracks indexing operations on the tape. -*/ -template -class VecAD { - friend bool Parameter (const VecAD &vec); - friend bool Variable (const VecAD &vec); - friend class ADTape; - friend class VecAD_reference; - - friend std::ostream& operator << - (std::ostream &os, const VecAD &vec_); -private: - /// size of this VecAD vector - const size_t length_; - - /// elements of this vector - pod_vector data_; - - /// offset in cummulate vector corresponding to this object - size_t offset_; - - /// tape id corresponding to the offset - tape_id_t tape_id_; -public: - /// declare the user's view of this type here - typedef VecAD_reference reference; - - /// default constructor - /// initialize tape_id_ same as for default constructor; see default.hpp - VecAD(void) - : length_(0) - , offset_(0) - , tape_id_(0) - { CPPAD_ASSERT_UNKNOWN( Parameter(*this) ); } - - /// sizing constructor - /// initialize tape_id_ same as for parameters; see ad_copy.hpp - VecAD(size_t n) - : length_(n) - , offset_(0) - , tape_id_(0) - { if( length_ > 0 ) - { size_t i; - Base zero(0); - data_.extend(length_); - - // Initialize data to zero so all have same value. - // This uses less memory and avoids a valgrind error - // during TapeRec::PutPar - for(i = 0; i < length_; i++) - data_[i] = zero; - } - CPPAD_ASSERT_UNKNOWN( Parameter(*this) ); - } - - /// destructor - ~VecAD(void) - { } - - /// number of elements in the vector - size_t size(void) - { return length_; } - - /// element access (not taped) - /// - /// \param i - /// element index - Base &operator[](size_t i) - { - CPPAD_ASSERT_KNOWN( - Parameter(*this), - "VecAD: cannot use size_t indexing because this" - " VecAD vector is a variable." - ); - CPPAD_ASSERT_KNOWN( - i < length_, - "VecAD: element index is >= vector length" - ); - - return data_[i]; - } - - /*! delayed taped elemement access - - \param x - element index - - \par - This operation may convert this vector from a parameter to a variable - */ - VecAD_reference operator[](const AD &x) - { - CPPAD_ASSERT_KNOWN( - 0 <= Integer(x), - "VecAD: element index is less than zero" - ); - CPPAD_ASSERT_KNOWN( - static_cast( Integer(x) ) < length_, - "VecAD: element index is >= vector length" - ); - - // if no need to track indexing operation, return now - if( Parameter(*this) & Parameter(x) ) - return VecAD_reference(this, x); - - CPPAD_ASSERT_KNOWN( - Parameter(*this) | Parameter(x) | (tape_id_ == x.tape_id_), - "VecAD: vector and index are variables for" - " different tapes." - ); - - if( Parameter(*this) ) - { // must place a copy of vector in tape - offset_ = - AD::tape_ptr(x.tape_id_)->AddVec(length_, data_); - - // Advance pointer by one so starts at first component of this - // vector; i.e., skip lenght at begining (so is always > 0) - offset_++; - - // tape id corresponding to this offest - tape_id_ = x.tape_id_; - } - - return VecAD_reference(this, x); - } - -}; - - -/*! -Taped setting of element to a value. - -\param y -value that element is set to. -*/ -template -void VecAD_reference::operator=(const AD &y) -{ - if( Parameter(y) ) - { // fold into the Base type assignment - *this = y.value_; - return; - } - CPPAD_ASSERT_UNKNOWN( y.taddr_ > 0 ); - - CPPAD_ASSERT_KNOWN( - Parameter(*vec_) | (vec_->tape_id_ == y.tape_id_), - "VecAD assignment: vector and new element value are variables" - "\nfor different tapes." - ); - - ADTape* tape = AD::tape_ptr(y.tape_id_); - CPPAD_ASSERT_UNKNOWN( tape != CPPAD_NULL ); - if( Parameter(*vec_) ) - { // must place a copy of vector in tape - vec_->offset_ = tape->AddVec(vec_->length_, vec_->data_); - - // advance offset to be start of vector plus one - (vec_->offset_)++; - - // tape id corresponding to this offest - vec_->tape_id_ = y.tape_id_; - } - CPPAD_ASSERT_UNKNOWN( Variable(*vec_) ); - - - // index in vector for this element - size_t i = static_cast( Integer(ind_) ); - CPPAD_ASSERT_UNKNOWN( i < vec_->length_ ); - - // assign value for this element (as an AD object) - vec_->data_[i] = y.value_; - - // record the setting of this array element - CPPAD_ASSERT_UNKNOWN( vec_->offset_ > 0 ); - if( Parameter(ind_) ) - { CPPAD_ASSERT_UNKNOWN( NumArg(StpvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(StpvOp) == 0 ); - - // put operand addresses in tape - tape->Rec_.PutArg(vec_->offset_, i, y.taddr_); - - // put operator in the tape, ind_ is parameter, y is variable - tape->Rec_.PutOp(StpvOp); - } - else - { CPPAD_ASSERT_UNKNOWN( NumArg(StvvOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(StvvOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( ind_.taddr_ > 0 ); - - // put operand addresses in tape - tape->Rec_.PutArg(vec_->offset_, ind_.taddr_, y.taddr_); - - // put operator in the tape, ind_ is variable, y is variable - tape->Rec_.PutOp(StvvOp); - } -} - - -/*! -Taped setting of element to a value. - -\param y -value that element is set to. -*/ -template -void VecAD_reference::operator=(const Base &y) -{ - size_t i = static_cast( Integer(ind_) ); - CPPAD_ASSERT_UNKNOWN( i < vec_->length_ ); - - // assign value for this element - vec_->data_[i] = y; - - // check if this ADVec object is a parameter - if( Parameter(*vec_) ) - return; - - ADTape* tape = AD::tape_ptr(vec_->tape_id_); - CPPAD_ASSERT_UNKNOWN( tape != CPPAD_NULL ); - - // put value of the parameter y in the tape - addr_t p = tape->Rec_.PutPar(y); - - // record the setting of this array element - CPPAD_ASSERT_UNKNOWN( vec_->offset_ > 0 ); - if( Parameter(ind_) ) - { CPPAD_ASSERT_UNKNOWN( NumArg(StppOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(StppOp) == 0 ); - - // put operand addresses in tape - tape->Rec_.PutArg(vec_->offset_, i, p); - - // put operator in the tape, ind_ is parameter, y is parameter - tape->Rec_.PutOp(StppOp); - } - else - { CPPAD_ASSERT_UNKNOWN( NumArg(StvpOp) == 3 ); - CPPAD_ASSERT_UNKNOWN( NumRes(StvpOp) == 0 ); - CPPAD_ASSERT_UNKNOWN( ind_.taddr_ > 0 ); - - // put operand addresses in tape - tape->Rec_.PutArg(vec_->offset_, ind_.taddr_, p); - - // put operator in the tape, ind_ is variable, y is parameter - tape->Rec_.PutOp(StvpOp); - } -} - -/*! -Taped setting of element to a value. - -\param y -value that element is set to. - -\par -this case gets folded into case where value is AD. -*/ -template -inline void VecAD_reference::operator= -(const VecAD_reference &y) -{ *this = y.ADBase(); } - -/*! -Taped setting of element to a value. - -\param y -value that element is set to. - -\par -this case gets folded into case where value is Base. -*/ -template -inline void VecAD_reference::operator=(int y) -{ *this = Base(y); } - - -} // END_CPPAD_NAMESPACE - -// preprocessor symbols that are local to this file -# undef CPPAD_VEC_AD_COMPUTED_ASSIGNMENT - -# endif diff --git a/ct_core/include/ct/external/cppad/local/zdouble.hpp b/ct_core/include/ct/external/cppad/local/zdouble.hpp deleted file mode 100644 index 040ad0202..000000000 --- a/ct_core/include/ct/external/cppad/local/zdouble.hpp +++ /dev/null @@ -1,550 +0,0 @@ -// $Id$ -# ifndef CPPAD_ZDOUBLE_HPP -# define CPPAD_ZDOUBLE_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin zdouble$$ -$spell - zdouble - op - bool - inf - CppAD -$$ -$section zdouble: An AD Base Type With Absolute Zero$$ - -$head Deprecated 2015-09-26$$ -Use the function $cref azmul$$ instead. - -$head Absolute Zero$$ -The $code zdouble$$ class acts like the $code double$$ type -with the added property that zero times any value is zero. -This includes zero time $cref nan$$ and zero times infinity. -In addition, zero divided by any value and any value times zero -are also zero. - -$head Syntax$$ - -$subhead Constructor and Assignment$$ -$codei% zdouble z -%$$ -$codei% zdouble z(x) -%$$ -$icode% z1% %op% %x% -%$$ -where $icode x$$ is a $code double$$ or $code zdouble$$ object -and $icode op$$ is $code =$$, $code +=$$, $code -=$$, $code *=$$ -or $code /=-$$. - -$subhead Comparison Operators$$ -$icode% b% = %z% %op% %x% -%$$ -$icode% b% = %x% %op% %z% -%$$ -where $icode b$$ is a $code bool$$ object, -$icode z$$ is a $code zdouble$$ object, -$icode x$$ is a $code double$$ or $code zdouble$$ object, and -$icode op$$ is $code ==$$, $code !=$$, $code <=$$, $code >=$$, -$code <$$ or $code >$$. - -$subhead Arithmetic Operators$$ -$icode% z2% = %z1% %op% %x% -%$$ -$icode% z2% = %x% %op% %z1% -%$$ -where $icode z1$$, $icode z2$$ are $code zdouble$$ objects, -$icode x$$ is a $code double$$ or $code zdouble$$ object, and -$icode op$$ is $code +$$, $code -$$, $code *$$ or $code /$$. - - -$subhead Standard Math$$ -$icode% z2% = %fun%(%z1%) -%$$ -$icode% z3% = pow(%z1%, %z2%) -%$$ -where $icode z1$$, $icode z2$$, $icode z3$$ are $code zdouble$$ objects and -$icode fun$$ is a $cref unary_standard_math$$ function. - -$subhead Nan$$ -There is a specialization of $cref nan$$ so that -$icode% - z2% = nan(%z1%) -%$$ -returns 'not a number' when $icode z1$$ has type $code zdouble$$. -Note that this template function needs to be specialized because -$codei - zdouble(0.0) == zdouble(0.0) / zdouble(0.0) -$$ - - -$head Motivation$$ - -$subhead General$$ -Often during computing (and more so in parallel computing) alternative -values for an expression are computed and one of the alternatives -is chosen using some boolean variable. -This is often represented by -$codei% - %result% = %flag% * %value_if_true% + (1 - %flag%) * %value_if_false% -%$$ -where $icode flag$$ is one for true and zero for false. -This representation does not work for $code double$$ when the value -being multiplied by zero is $code +inf$$, $code -inf$$, or $code nan$$. - -$subhead CppAD$$ -In CppAD one can use -$cref/conditional expressions/CondExp/$$ to achieve the representation -$codei% - %result% = %flag% * %value_if_true% + (1 - %flag%) * %value_if_false% -%$$ -This works fine except when there are -$cref/multiple levels of AD/mul_level/$$; e.g., -when using $codei%AD< AD >%$$. -In this case the corresponding AD function objects have type -$cref/ADFun< AD >/FunConstruct/$$. -When these AD function objects compute derivatives using -$cref reverse$$ mode, the conditional expressions are represented use -zeros to multiply the expression that is not used. -Using $codei%AD< AD >%$$ instead of $code AD< AD >$$ -makes this representation work and fixes the problem. - -$head Base Type Requirements$$ -The type $code zdouble$$ satisfies all of the CppAD -$cref/base type requirements/base_require/$$. - -$children% - test_more/zdouble.cpp -%$$ -$head Example$$ -The file $cref zdouble.cpp$$ -contains an example and test of this class. -It returns true if it succeeds and false otherwise. - -$end -*/ -# include -# include - -/*! -\file zdouble.hpp -Define a class like double but with an absolute zero. -*/ - -/*! -\def CPPAD_ZDOUBLE_NORMAL_ASSIGN_OPERATOR(op) -Define a computed assignment member operator that functions the same -as corresponding double operator. -*/ -# define CPPAD_ZDOUBLE_NORMAL_ASSIGN_OPERATOR(op) \ - zdouble& operator op (const zdouble& z) \ - { dbl_ op z.dbl_; \ - return *this; \ - } \ - zdouble& operator op (const double& x) \ - { dbl_ op x; \ - return *this; \ - } - -/*! -\def CPPAD_ZDOUBLE_UNARY_OPERATOR(op) -Define a unary computed assignment member operator. -*/ -# define CPPAD_ZDOUBLE_UNARY_OPERATOR(op) \ - zdouble operator op (void) const \ - { return zdouble( op dbl_ ); } - -/*! -# define CPPAD_ZDOUBLE_NORMAL_BINARY_OPERATOR(op) -Define a binary arithmetic member operator that functions the same -as corresponding double operator. -*/ -# define CPPAD_ZDOUBLE_NORMAL_BINARY_OPERATOR(op) \ - zdouble operator op (const zdouble& z) const \ - { return zdouble( dbl_ op z.dbl_ ); } \ - zdouble operator op (const double& x) const \ - { return zdouble( dbl_ op x ); } - -/*! -\def CPPAD_ZDOUBLE_COMPARE_OPERATOR(op) -Define a comparison member operator. -*/ -# define CPPAD_ZDOUBLE_COMPARE_OPERATOR(op) \ - bool operator op (const zdouble& z) const \ - { return dbl_ op z.dbl_; } \ - bool operator op (const double& x) const \ - { return dbl_ op x; } - -/*! -\def CPPAD_ZDOUBLE_OTHER_BINARY_OPERATOR(op) -Define a binary arithmetic operator that is not a member because -the double operand is on the left. -*/ -# define CPPAD_ZDOUBLE_OTHER_BINARY_OPERATOR(op) \ - inline zdouble operator op(const double& x, const zdouble& z) \ - { return zdouble(x) op z; } - -/*! -\def CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(op, op_switch) -Define a comparison operator that is not a member because -the double operand is on the left. -Convert it to the case where the double operand is on the right by -by using op_switch instead of op. -*/ -# define CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(op, op_switch) \ - inline bool operator op(const double& x, const zdouble& z) \ - { return z op_switch x; } - -/*! -\def CPPAD_ZDOUBLE_STD_MATH_FRIEND(fun) -Declare that a standard math function is a friend. -*/ -# define CPPAD_ZDOUBLE_STD_MATH_FRIEND(fun) \ - friend zdouble fun(const zdouble& z); -/*! -\def CPPAD_ZDOUBLE_STD_MATH(fun) -Define a standard math function. -*/ -# define CPPAD_ZDOUBLE_STD_MATH(fun) \ - inline zdouble fun(const zdouble& z ) \ - { return zdouble( std::fun(z.dbl_) ); } - -namespace CppAD { // CPPAD_BEGIN_NAMESPACDE - - -/*! -Class that is like double, except that it has an absolute zero. -*/ -class zdouble { - /*! - For zdouble objects z1, z2, and std::ostream os, - declare the following friends: - \code - os << z1 - Integer(z1) - abs(z1) - pow(z1, z2) - abs_geq(z1, z2) - fun(z1) - \endcode - where fun is any of the standard math unary functions. - */ - friend std::ostream& operator << (std::ostream &os, const zdouble& z); - friend int Integer(const zdouble& z); - friend zdouble abs(const zdouble& x); - friend zdouble pow(const zdouble& x, const zdouble& y); - friend bool abs_geq(const zdouble& x, const zdouble& y); - // - CPPAD_ZDOUBLE_STD_MATH_FRIEND(acos) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(asin) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(atan) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(cos) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(cosh) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(exp) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(fabs) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(log) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(log10) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(sin) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(sinh) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(sqrt) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(tan) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(tanh) - // -# if CPPAD_USE_CPLUSPLUS_2011 - CPPAD_ZDOUBLE_STD_MATH_FRIEND(erf) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(asinh) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(acosh) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(atanh) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(expm1) - CPPAD_ZDOUBLE_STD_MATH_FRIEND(log1p) - // -# endif -private: - /// The value for this object - double dbl_; -public: - /// Default constructor - zdouble(void) - : dbl_() - { } - /// Copy constructor - zdouble(const zdouble& z) - : dbl_(z.dbl_) - { } - /// Constructor from double - zdouble(const double& dbl) - : dbl_(dbl) - { } - // - /// Destructor - ~zdouble(void) - { } - // - /// Assignment from zdouble - zdouble& operator=(const zdouble& z) - { dbl_ = z.dbl_; - return *this; - } - /// Assignment from double - zdouble& operator=(const double& dbl) - { dbl_ = dbl; - return *this; - } - // - /// Normal computed assignment - CPPAD_ZDOUBLE_NORMAL_ASSIGN_OPERATOR(+=) - /// Normal computed assignment - CPPAD_ZDOUBLE_NORMAL_ASSIGN_OPERATOR(-=) - /// Normal unary operator - CPPAD_ZDOUBLE_UNARY_OPERATOR(+) - /// Normal unary operator - CPPAD_ZDOUBLE_UNARY_OPERATOR(-) - /// Normal compare operator - CPPAD_ZDOUBLE_COMPARE_OPERATOR(==) - /// Normal compare operator - CPPAD_ZDOUBLE_COMPARE_OPERATOR(!=) - /// Normal compare operator - CPPAD_ZDOUBLE_COMPARE_OPERATOR(<=) - /// Normal compare operator - CPPAD_ZDOUBLE_COMPARE_OPERATOR(>=) - /// Normal compare operator - CPPAD_ZDOUBLE_COMPARE_OPERATOR(<) - /// Normal compare operator - CPPAD_ZDOUBLE_COMPARE_OPERATOR(>) - // - /// Normal binary arithmetic operator - CPPAD_ZDOUBLE_NORMAL_BINARY_OPERATOR(+) - /// Normal binary arithmetic operator - CPPAD_ZDOUBLE_NORMAL_BINARY_OPERATOR(-) - // - /// Binary arithmetic * with absolute zero - zdouble operator * (const zdouble& z) const - { bool zero = (dbl_ == 0.0) || (z.dbl_ == 0.0); - return zdouble( zero ? 0.0 : (dbl_ * z.dbl_) ); - } - /// Binary arithmetic * with absolute zero - zdouble operator * (const double& x) const - { bool zero = (dbl_ == 0.0) || (x == 0.0); - return zdouble( zero ? 0.0 : (dbl_ * x) ); - } - /// Binary arithmetic / with absolute zero - zdouble operator / (const zdouble& z) const - { bool zero = (dbl_ == 0.0); - return zdouble( zero ? 0.0 : (dbl_ / z.dbl_) ); - } - /// Binary arithmetic / with absolute zero - zdouble operator / (const double& x) const - { bool zero = (dbl_ == 0.0); - return zdouble( zero ? 0.0 : (dbl_ / x) ); - } - // - /// Compute assignmnet *= with absolute zero - zdouble& operator *= (const zdouble& z) - { bool zero = (dbl_ == 0.0) || (z.dbl_ == 0.0); - zero ? (dbl_ = 0.0) : (dbl_ *= z.dbl_); - return *this; - } - /// Compute assignmnet *= with absolute zero - zdouble& operator *= (const double& x) - { bool zero = (dbl_ == 0.0) || (x == 0.0); - zero ? (dbl_ = 0.0) : (dbl_ *= x); - return *this; - } - // - /// Compute assignmnet /= with absolute zero - zdouble& operator /= (const zdouble& z) - { bool zero = (dbl_ == 0.0); - zero ? (dbl_ = 0.0) : (dbl_ /= z.dbl_); - return *this; - } - /// Compute assignmnet /= with absolute zero - zdouble& operator /= (const double& x) - { bool zero = (dbl_ == 0.0); - zero ? (dbl_ = 0.0) : (dbl_ /= x); - return *this; - } -}; -// BEGIN nan -/// Must specialize CppAD::nan because zdouble 0/0 is not nan. -template <> -inline zdouble nan(const zdouble& zero) -{ - return zdouble( std::numeric_limits::quiet_NaN() ); -} -// END nan -// -/// Normal non-member compare operator -CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(==, ==) -/// Normal non-member compare operator -CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(!=, !=) -/// Normal non-member compare operator -CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(<=, >=) -/// Normal non-member compare operator -CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(>=, <=) -/// Normal non-member compare operator -CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(<, >) -/// Normal non-member compare operator -CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR(>, <) -// -/// Normal binary arithmetic operator -CPPAD_ZDOUBLE_OTHER_BINARY_OPERATOR(+) -/// Normal binary arithmetic operator -CPPAD_ZDOUBLE_OTHER_BINARY_OPERATOR(-) -/// Binary arithmetic operator with absolute zero -CPPAD_ZDOUBLE_OTHER_BINARY_OPERATOR(*) -/// Binary arithmetic operator with absolute zero -CPPAD_ZDOUBLE_OTHER_BINARY_OPERATOR(/) -// ------------------------------------------------------------------------- -// Base type requirements -// ------------------------------------------------------------------------- - -/// Base type requirement: CondExpOp -inline zdouble CondExpOp( - enum CompareOp cop , - const zdouble& left , - const zdouble& right , - const zdouble& exp_if_true , - const zdouble& exp_if_false ) -{ return CondExpTemplate(cop, left, right, exp_if_true, exp_if_false); -} - -/// Base type requirement: CondExpRel -CPPAD_COND_EXP_REL(zdouble) - -/// Base type requirement: EqualOpSeq -inline bool EqualOpSeq(const zdouble& x, const zdouble& y) -{ return x == y; } - -/// Base type requirement: Identical -inline bool IdenticalPar(const zdouble& x) -{ return true; } -inline bool IdenticalZero(const zdouble& x) -{ return (x == 0.0); } -inline bool IdenticalOne(const zdouble& x) -{ return (x == 1.); } -inline bool IdenticalEqualPar(const zdouble& x, const zdouble& y) -{ return (x == y); } - -/// Base type requirement: output operator -inline std::ostream& operator << (std::ostream &os, const zdouble& z) -{ os << z.dbl_; - return os; -} - -/// Base type requirement: Integer -inline int Integer(const zdouble& x) -{ return static_cast(x.dbl_); } - -/// Base type requirement: azmul -inline zdouble azmul(const zdouble& x, const zdouble& y) -{ return x * y; } - -/// Base type requirement: Ordered -inline bool GreaterThanZero(const zdouble& x) -{ return x > 0.0; } -inline bool GreaterThanOrZero(const zdouble& x) -{ return x >= 0.0; } -inline bool LessThanZero(const zdouble& x) -{ return x < 0.0; } -inline bool LessThanOrZero(const zdouble& x) -{ return x <= 0.0; } -inline bool abs_geq(const zdouble& x, const zdouble& y) -{ return std::fabs(x.dbl_) >= std::fabs(y.dbl_); } - -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(acos) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(asin) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(atan) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(cos) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(cosh) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(exp) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(fabs) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(log) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(log10) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(sin) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(sinh) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(sqrt) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(tan) -/// Normal standard math function -CPPAD_ZDOUBLE_STD_MATH(tanh) -// -# if CPPAD_USE_CPLUSPLUS_2011 -/// C++2011 standard math function -CPPAD_ZDOUBLE_STD_MATH(erf) -/// C++2011 standard math function -CPPAD_ZDOUBLE_STD_MATH(asinh) -/// C++2011 standard math function -CPPAD_ZDOUBLE_STD_MATH(acosh) -/// C++2011 standard math function -CPPAD_ZDOUBLE_STD_MATH(atanh) -/// C++2011 standard math function -CPPAD_ZDOUBLE_STD_MATH(expm1) -/// C++2011 standard math function -CPPAD_ZDOUBLE_STD_MATH(log1p) -# endif - -/// Base type requirement: abs -inline zdouble abs(const zdouble& x) -{ return std::fabs(x.dbl_); } - -/// Base type requirement: sign -inline zdouble sign(const zdouble& x) -{ if( x > 0.0 ) - return zdouble(1.); - if( x == 0.0 ) - return zdouble(0.0); - return zdouble(-1.); -} - -/// Base type requirement: pow -inline zdouble pow(const zdouble& x, const zdouble& y) -{ return std::pow(x.dbl_, y.dbl_); } - -/// Base type requirement: limits -template <> -class numeric_limits { -public: - // machine epsilon - static zdouble epsilon(void) - { return std::numeric_limits::epsilon(); } - // minimum positive normalized value - static zdouble min(void) - { return std::numeric_limits::min(); } - // maximum finite value - static zdouble max(void) - { return std::numeric_limits::max(); } -}; - -} // CPPAD_END_NAMESPACE - -/// undef all macros defined in this file -# undef CPPAD_ZDOUBLE_NORMAL_ASSIGN_OPERATOR -# undef CPPAD_ZDOUBLE_UNARY_OPERATOR -# undef CPPAD_ZDOUBLE_NORMAL_BINARY_OPERATOR -# undef CPPAD_ZDOUBLE_COMPARE_OPERATOR -# undef CPPAD_ZDOUBLE_OTHER_BINARY_OPERATOR -# undef CPPAD_ZDOUBLE_OTHER_COMPARE_OPERATOR -# undef CPPAD_ZDOUBLE_STD_MATH_FRIEND -# undef CPPAD_ZDOUBLE_STD_MATH - -# endif diff --git a/ct_core/include/ct/external/cppad/local/zmul_op.hpp b/ct_core/include/ct/external/cppad/local/zmul_op.hpp deleted file mode 100644 index 92d26af40..000000000 --- a/ct_core/include/ct/external/cppad/local/zmul_op.hpp +++ /dev/null @@ -1,518 +0,0 @@ -// $Id$ -# ifndef CPPAD_ZMUL_OP_HPP -# define CPPAD_ZMUL_OP_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file mul_op.hpp -Forward and reverse mode calculations for z = azmul(x, y). -*/ - -// --------------------------- Zmulvv ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = ZmulvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = azmul(x, y) -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_binary_op -*/ - -template -inline void forward_zmulvv_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ZmulvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ZmulvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - size_t k; - for(size_t d = p; d <= q; d++) - { z[d] = Base(0); - for(k = 0; k <= d; k++) - z[d] += azmul(x[d-k], y[k]); - } -} -/*! -Multiple directions forward mode Taylor coefficients for op = ZmulvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = azmul(x, y) -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_binary_op_dir -*/ - -template -inline void forward_zmulvv_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ZmulvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ZmulvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to arguments and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - Base* x = taylor + arg[0] * num_taylor_per_var; - Base* y = taylor + arg[1] * num_taylor_per_var; - Base* z = taylor + i_z * num_taylor_per_var; - - size_t k, ell, m; - for(ell = 0; ell < r; ell++) - { m = (q-1)*r + ell + 1; - z[m] = azmul(x[0], y[m]) + azmul(x[m], y[0]); - for(k = 1; k < q; k++) - z[m] += azmul(x[(q-k-1)*r + ell + 1], y[(k-1)*r + ell + 1]); - } -} - -/*! -Compute zero order forward mode Taylor coefficients for result of op = ZmulvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = azmul(x, y) -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails forward_binary_op_0 -*/ - -template -inline void forward_zmulvv_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ZmulvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ZmulvvOp) == 1 ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = azmul(x[0], y[0]); -} - -/*! -Compute reverse mode partial derivatives for result of op = ZmulvvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = azmul(x, y) -\endverbatim -In the documentation below, -this operations is for the case where both x and y are variables -and the argument \a parameter is not used. - -\copydetails reverse_binary_op -*/ - -template -inline void reverse_zmulvv_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ZmulvvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ZmulvvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Arguments - const Base* x = taylor + arg[0] * cap_order; - const Base* y = taylor + arg[1] * cap_order; - - // Partial derivatives corresponding to arguments and result - Base* px = partial + arg[0] * nc_partial; - Base* py = partial + arg[1] * nc_partial; - Base* pz = partial + i_z * nc_partial; - - // number of indices to access - size_t j = d + 1; - size_t k; - while(j) - { --j; - for(k = 0; k <= j; k++) - { - px[j-k] += azmul(pz[j], y[k]); - py[k] += azmul(pz[j], x[j-k]); - } - } -} -// --------------------------- Zmulpv ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = ZmulpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = azmul(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op -*/ - -template -inline void forward_zmulpv_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ZmulpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ZmulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to arguments and result - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - // Paraemter value - Base x = parameter[ arg[0] ]; - - for(size_t d = p; d <= q; d++) - z[d] = azmul(x, y[d]); -} -/*! -Multiple directions forward mode Taylor coefficients for op = ZmulpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = azmul(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op_dir -*/ - -template -inline void forward_zmulpv_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ZmulpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ZmulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to arguments and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - size_t m = (q-1) * r + 1; - Base* y = taylor + arg[1] * num_taylor_per_var + m; - Base* z = taylor + i_z * num_taylor_per_var + m; - - // Paraemter value - Base x = parameter[ arg[0] ]; - - for(size_t ell = 0; ell < r; ell++) - z[ell] = azmul(x, y[ell]); -} -/*! -Compute zero order forward mode Taylor coefficient for result of op = ZmulpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = azmul(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op_0 -*/ - -template -inline void forward_zmulpv_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ZmulpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ZmulpvOp) == 1 ); - - // Paraemter value - Base x = parameter[ arg[0] ]; - - // Taylor coefficients corresponding to arguments and result - Base* y = taylor + arg[1] * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = azmul(x, y[0]); -} - -/*! -Compute reverse mode partial derivative for result of op = ZmulpvOp. - -The C++ source code corresponding to this operation is -\verbatim - z = azmul(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails reverse_binary_op -*/ - -template -inline void reverse_zmulpv_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ZmulpvOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ZmulpvOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Arguments - Base x = parameter[ arg[0] ]; - - // Partial derivatives corresponding to arguments and result - Base* py = partial + arg[1] * nc_partial; - Base* pz = partial + i_z * nc_partial; - - // number of indices to access - size_t j = d + 1; - while(j) - { --j; - py[j] += azmul(pz[j], x); - } -} -// --------------------------- Zmulvp ----------------------------------------- -/*! -Compute forward mode Taylor coefficients for result of op = ZmulvpOp. - -The C++ source code corresponding to this operation is -\verbatim - z = azmul(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op -*/ - -template -inline void forward_zmulvp_op( - size_t p , - size_t q , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ZmulvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ZmulvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - CPPAD_ASSERT_UNKNOWN( p <= q ); - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* z = taylor + i_z * cap_order; - - // Paraemter value - Base y = parameter[ arg[1] ]; - - for(size_t d = p; d <= q; d++) - z[d] = azmul(x[d], y); -} -/*! -Multiple directions forward mode Taylor coefficients for op = ZmulvpOp. - -The C++ source code corresponding to this operation is -\verbatim - z = azmul(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op_dir -*/ - -template -inline void forward_zmulvp_op_dir( - size_t q , - size_t r , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ZmulvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ZmulvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( 0 < q ); - CPPAD_ASSERT_UNKNOWN( q < cap_order ); - - // Taylor coefficients corresponding to arguments and result - size_t num_taylor_per_var = (cap_order-1) * r + 1; - size_t m = (q-1) * r + 1; - Base* x = taylor + arg[0] * num_taylor_per_var + m; - Base* z = taylor + i_z * num_taylor_per_var + m; - - // Paraemter value - Base y = parameter[ arg[1] ]; - - for(size_t ell = 0; ell < r; ell++) - z[ell] = azmul(x[ell], y); -} -/*! -Compute zero order forward mode Taylor coefficient for result of op = ZmulvpOp. - -The C++ source code corresponding to this operation is -\verbatim - z = azmul(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails forward_binary_op_0 -*/ - -template -inline void forward_zmulvp_op_0( - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - Base* taylor ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ZmulvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ZmulvpOp) == 1 ); - - // Paraemter value - Base y = parameter[ arg[1] ]; - - // Taylor coefficients corresponding to arguments and result - Base* x = taylor + arg[0] * cap_order; - Base* z = taylor + i_z * cap_order; - - z[0] = azmul(x[0], y); -} - -/*! -Compute reverse mode partial derivative for result of op = ZmulvpOp. - -The C++ source code corresponding to this operation is -\verbatim - z = azmul(x, y) -\endverbatim -In the documentation below, -this operations is for the case where x is a parameter and y is a variable. - -\copydetails reverse_binary_op -*/ - -template -inline void reverse_zmulvp_op( - size_t d , - size_t i_z , - const addr_t* arg , - const Base* parameter , - size_t cap_order , - const Base* taylor , - size_t nc_partial , - Base* partial ) -{ - // check assumptions - CPPAD_ASSERT_UNKNOWN( NumArg(ZmulvpOp) == 2 ); - CPPAD_ASSERT_UNKNOWN( NumRes(ZmulvpOp) == 1 ); - CPPAD_ASSERT_UNKNOWN( d < cap_order ); - CPPAD_ASSERT_UNKNOWN( d < nc_partial ); - - // Arguments - Base y = parameter[ arg[1] ]; - - // Partial derivatives corresponding to arguments and result - Base* px = partial + arg[0] * nc_partial; - Base* pz = partial + i_z * nc_partial; - - // number of indices to access - size_t j = d + 1; - while(j) - { --j; - px[j] += azmul(pz[j], y); - } -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/speed/det_33.hpp b/ct_core/include/ct/external/cppad/speed/det_33.hpp deleted file mode 100644 index 0867c9957..000000000 --- a/ct_core/include/ct/external/cppad/speed/det_33.hpp +++ /dev/null @@ -1,117 +0,0 @@ -// $Id: det_33.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_DET_33_HPP -# define CPPAD_DET_33_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin det_33$$ -$spell - cppad - CppAD - det - cppad.hpp - namespace - const - bool -$$ - -$section Check Determinant of 3 by 3 matrix$$ -$mindex det_33 correct$$ - - -$head Syntax$$ -$codei%# include -%$$ -$icode%ok% = det_33(%x%, %d%)%$$ - -$head Purpose$$ -This routine can be used to check a method for computing -the determinant of a matrix. - -$head Inclusion$$ -The template function $code det_33$$ is defined in the $code CppAD$$ -namespace by including -the file $code cppad/speed/det_33.hpp$$ -(relative to the CppAD distribution directory). -It is only intended for example and testing purposes, -so it is not automatically included by -$cref/cppad.hpp/cppad/$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$. -It contains the elements of the matrix $latex X$$ in row major order; i.e., -$latex \[ - X_{i,j} = x [ i * 3 + j ] -\] $$ - -$head d$$ -The argument $icode d$$ has prototype -$codei% - const %Vector% &%d% -%$$. -It is tested to see if $icode%d%[0]%$$ it is equal to $latex \det ( X )$$. - -$head Vector$$ -If $icode y$$ is a $icode Vector$$ object, -it must support the syntax -$codei% - %y%[%i%] -%$$ -where $icode i$$ has type $code size_t$$ with value less than 9. -This must return a $code double$$ value corresponding to the $th i$$ -element of the vector $icode y$$. -This is the only requirement of the type $icode Vector$$. -(Note that only the first element of the vector $icode d$$ is used.) - -$head ok$$ -The return value $icode ok$$ has prototype -$codei% - bool %ok% -%$$ -It is true, if the determinant $icode%d%[0]%$$ -passes the test and false otherwise. - -$children% - omh/det_33_hpp.omh -%$$ - -$head Source Code$$ -The file -$cref det_33.hpp$$ -contains the source code for this template function. - -$end ------------------------------------------------------------------------------- -*/ -// BEGIN C++ -# include -namespace CppAD { -template - bool det_33(const Vector &x, const Vector &d) - { bool ok = true; - - // use expansion by minors to compute the determinant by hand - double check = 0.; - check += x[0] * ( x[4] * x[8] - x[5] * x[7] ); - check -= x[1] * ( x[3] * x[8] - x[5] * x[6] ); - check += x[2] * ( x[3] * x[7] - x[4] * x[6] ); - - ok &= CppAD::NearEqual(check, d[0], 1e-10, 1e-10); - - return ok; - } -} -// END C++ -# endif diff --git a/ct_core/include/ct/external/cppad/speed/det_by_lu.hpp b/ct_core/include/ct/external/cppad/speed/det_by_lu.hpp deleted file mode 100644 index 7d1c1fb35..000000000 --- a/ct_core/include/ct/external/cppad/speed/det_by_lu.hpp +++ /dev/null @@ -1,195 +0,0 @@ -// $Id: det_by_lu.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_DET_BY_LU_HPP -# define CPPAD_DET_BY_LU_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin det_by_lu$$ -$spell - CppAD - cppad - lu - hpp - typedef - const - hpp - Det - CPPAD_TESTVECTOR - namespace -$$ - -$section Determinant Using Expansion by Lu Factorization$$ -$mindex det_by_lu factor$$ - - -$head Syntax$$ -$codei%# include -%$$ -$codei%det_by_lu<%Scalar%> %det%(%n%) -%$$ -$icode%d% = %det%(%a%) -%$$ - -$head Inclusion$$ -The template class $code det_by_lu$$ is defined in the $code CppAD$$ -namespace by including -the file $code cppad/speed/det_by_lu.hpp$$ -(relative to the CppAD distribution directory). -It is only intended for example and testing purposes, -so it is not automatically included by -$cref/cppad.hpp/cppad/$$. - -$head Constructor$$ -The syntax -$codei% - det_by_lu<%Scalar%> %det%(%n%) -%$$ -constructs the object $icode det$$ which can be used for -evaluating the determinant of $icode n$$ by $icode n$$ matrices -using LU factorization. - -$head Scalar$$ -The type $icode Scalar$$ can be any -$cref NumericType$$ - -$head n$$ -The argument $icode n$$ has prototype -$codei% - size_t %n% -%$$ - -$head det$$ -The syntax -$codei% - %d% = %det%(%a%) -%$$ -returns the determinant of the matrix $latex A$$ using LU factorization. - -$subhead a$$ -The argument $icode a$$ has prototype -$codei% - const %Vector% &%a% -%$$ -It must be a $icode Vector$$ with length $latex n * n$$ and with -It must be a $icode Vector$$ with length $latex n * n$$ and with -elements of type $icode Scalar$$. -The elements of the $latex n \times n$$ matrix $latex A$$ are defined, -for $latex i = 0 , \ldots , n-1$$ and $latex j = 0 , \ldots , n-1$$, by -$latex \[ - A_{i,j} = a[ i * m + j] -\] $$ - -$subhead d$$ -The return value $icode d$$ has prototype -$codei% - %Scalar% %d% -%$$ - -$head Vector$$ -If $icode y$$ is a $icode Vector$$ object, -it must support the syntax -$codei% - %y%[%i%] -%$$ -where $icode i$$ has type $code size_t$$ with value less than $latex n * n$$. -This must return a $icode Scalar$$ value corresponding to the $th i$$ -element of the vector $icode y$$. -This is the only requirement of the type $icode Vector$$. - -$children% - speed/example/det_by_lu.cpp% - omh/det_by_lu_hpp.omh -%$$ - - -$head Example$$ -The file -$cref det_by_lu.cpp$$ -contains an example and test of $code det_by_lu.hpp$$. -It returns true if it succeeds and false otherwise. - -$head Source Code$$ -The file -$cref det_by_lu.hpp$$ -contains the source for this template function. - - -$end ---------------------------------------------------------------------------- -*/ -// BEGIN C++ -# include -# include - -// BEGIN CppAD namespace -namespace CppAD { - -// The AD complex case is used by examples by not used by speed tests -// Must define a specializatgion of LeqZero,AbsGeq for the ADComplex case -typedef std::complex Complex; -typedef CppAD::AD ADComplex; -CPPAD_BOOL_UNARY(Complex, LeqZero ) -CPPAD_BOOL_BINARY(Complex, AbsGeq ) - -template -class det_by_lu { -private: - const size_t m_; - const size_t n_; - CPPAD_TESTVECTOR(Scalar) A_; - CPPAD_TESTVECTOR(Scalar) B_; - CPPAD_TESTVECTOR(Scalar) X_; -public: - det_by_lu(size_t n) : m_(0), n_(n), A_(n * n) - { } - - template - inline Scalar operator()(const Vector &x) - { - using CppAD::exp; - - Scalar logdet; - Scalar det; - int signdet; - size_t i; - - // copy matrix so it is not overwritten - for(i = 0; i < n_ * n_; i++) - A_[i] = x[i]; - - // comput log determinant - signdet = CppAD::LuSolve( - n_, m_, A_, B_, X_, logdet); - -/* - // Do not do this for speed test because it makes floating - // point operation sequence very simple. - if( signdet == 0 ) - det = 0; - else det = Scalar( signdet ) * exp( logdet ); -*/ - - // convert to determinant - det = Scalar( signdet ) * exp( logdet ); - -# ifdef FADBAD - // Fadbad requires tempories to be set to constants - for(i = 0; i < n_ * n_; i++) - A_[i] = 0; -# endif - - return det; - } -}; -} // END CppAD namespace -// END C++ -# endif diff --git a/ct_core/include/ct/external/cppad/speed/det_by_minor.hpp b/ct_core/include/ct/external/cppad/speed/det_by_minor.hpp deleted file mode 100644 index 3dfc26ff7..000000000 --- a/ct_core/include/ct/external/cppad/speed/det_by_minor.hpp +++ /dev/null @@ -1,170 +0,0 @@ -// $Id: det_by_minor.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_DET_BY_MINOR_HPP -# define CPPAD_DET_BY_MINOR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin det_by_minor$$ -$spell - CppAD - cppad - typedef - const - hpp - Det - namespace -$$ - -$section Determinant Using Expansion by Minors$$ - - - -$head Syntax$$ -$codei%# include -%$$ -$codei%det_by_minor<%Scalar%> %det%(%n%) -%$$ -$icode%d% = %det%(%a%) -%$$ - -$head Inclusion$$ -The template class $code det_by_minor$$ is defined in the $code CppAD$$ -namespace by including -the file $code cppad/speed/det_by_minor.hpp$$ -(relative to the CppAD distribution directory). -It is only intended for example and testing purposes, -so it is not automatically included by -$cref/cppad.hpp/cppad/$$. - -$head Constructor$$ -The syntax -$codei% - det_by_minor<%Scalar%> %det%(%n%) -%$$ -constructs the object $icode det$$ which can be used for -evaluating the determinant of $icode n$$ by $icode n$$ matrices -using expansion by minors. - -$head Scalar$$ -The type $icode Scalar$$ must satisfy the same conditions -as in the function $cref/det_of_minor/det_of_minor/Scalar/$$. - -$head n$$ -The argument $icode n$$ has prototype -$codei% - size_t %n% -%$$ - -$head det$$ -The syntax -$codei% - %d% = %det%(%a%) -%$$ -returns the determinant of the matrix $icode A$$ using expansion by minors. - -$subhead a$$ -The argument $icode a$$ has prototype -$codei% - const %Vector% &%a% -%$$ -It must be a $icode Vector$$ with length $latex n * n$$ and with -elements of type $icode Scalar$$. -The elements of the $latex n \times n$$ matrix $latex A$$ are defined, -for $latex i = 0 , \ldots , n-1$$ and $latex j = 0 , \ldots , n-1$$, by -$latex \[ - A_{i,j} = a[ i * m + j] -\] $$ - -$subhead d$$ -The return value $icode d$$ has prototype -$codei% - %Scalar% %d% -%$$ -It is equal to the determinant of $latex A$$. - -$head Vector$$ -If $icode y$$ is a $icode Vector$$ object, -it must support the syntax -$codei% - %y%[%i%] -%$$ -where $icode i$$ has type $code size_t$$ with value less than $latex n * n$$. -This must return a $icode Scalar$$ value corresponding to the $th i$$ -element of the vector $icode y$$. -This is the only requirement of the type $icode Vector$$. - -$children% - speed/example/det_by_minor.cpp% - omh/det_by_minor_hpp.omh -%$$ - - -$head Example$$ -The file -$cref det_by_minor.cpp$$ -contains an example and test of $code det_by_minor.hpp$$. -It returns true if it succeeds and false otherwise. - -$head Source Code$$ -The file -$cref det_by_minor.hpp$$ -contains the source for this template function. - - -$end ---------------------------------------------------------------------------- -*/ -// BEGIN C++ -# include -# include - -// BEGIN CppAD namespace -namespace CppAD { - -template -class det_by_minor { -private: - size_t m_; - - // made mutable because modified and then restored - mutable std::vector r_; - mutable std::vector c_; - - // make mutable because its value does not matter - mutable std::vector a_; -public: - det_by_minor(size_t m) : m_(m) , r_(m + 1) , c_(m + 1), a_(m * m) - { - size_t i; - - // values for r and c that correspond to entire matrix - for(i = 0; i < m; i++) - { r_[i] = i+1; - c_[i] = i+1; - } - r_[m] = 0; - c_[m] = 0; - } - - template - inline Scalar operator()(const Vector &x) const - { size_t i = m_ * m_; - while(i--) - a_[i] = x[i]; - return det_of_minor(a_, m_, m_, r_, c_); - } - -}; - -} // END CppAD namespace -// END C++ -# endif diff --git a/ct_core/include/ct/external/cppad/speed/det_grad_33.hpp b/ct_core/include/ct/external/cppad/speed/det_grad_33.hpp deleted file mode 100644 index 5e7549851..000000000 --- a/ct_core/include/ct/external/cppad/speed/det_grad_33.hpp +++ /dev/null @@ -1,132 +0,0 @@ -// $Id: det_grad_33.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_DET_GRAD_33_HPP -# define CPPAD_DET_GRAD_33_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin det_grad_33$$ -$spell - cppad - CppAD - det - cppad.hpp - namespace - const - bool -$$ - -$section Check Gradient of Determinant of 3 by 3 matrix$$ -$mindex det_grad_33 correct$$ - - -$head Syntax$$ -$codei%# include -%$$ -$icode%ok% = det_grad_33(%x%, %g%)%$$ - -$head Purpose$$ -This routine can be used to check a method for computing the -gradient of the determinant of a matrix. - -$head Inclusion$$ -The template function $code det_grad_33$$ is defined in the $code CppAD$$ -namespace by including -the file $code cppad/speed/det_grad_33.hpp$$ -(relative to the CppAD distribution directory). -It is only intended for example and testing purposes, -so it is not automatically included by -$cref/cppad.hpp/cppad/$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$. -It contains the elements of the matrix $latex X$$ in row major order; i.e., -$latex \[ - X_{i,j} = x [ i * 3 + j ] -\] $$ - -$head g$$ -The argument $icode g$$ has prototype -$codei% - const %Vector% &%g% -%$$. -It contains the elements of the gradient of -$latex \det ( X )$$ in row major order; i.e., -$latex \[ - \D{\det (X)}{X(i,j)} = g [ i * 3 + j ] -\] $$ - -$head Vector$$ -If $icode y$$ is a $icode Vector$$ object, -it must support the syntax -$codei% - %y%[%i%] -%$$ -where $icode i$$ has type $code size_t$$ with value less than 9. -This must return a $code double$$ value corresponding to the $th i$$ -element of the vector $icode y$$. -This is the only requirement of the type $icode Vector$$. - -$head ok$$ -The return value $icode ok$$ has prototype -$codei% - bool %ok% -%$$ -It is true, if the gradient $icode g$$ -passes the test and false otherwise. - -$children% - omh/det_grad_33_hpp.omh -%$$ - -$head Source Code$$ -The file -$cref det_grad_33.hpp$$ -contains the source code for this template function. - -$end ------------------------------------------------------------------------------- -*/ -// BEGIN C++ -# include -# include -namespace CppAD { -template - bool det_grad_33(const Vector &x, const Vector &g) - { bool ok = true; - typedef typename Vector::value_type Float; - Float eps = 10. * Float( std::numeric_limits::epsilon() ); - - // use expansion by minors to compute the derivative by hand - double check[9]; - check[0] = + ( x[4] * x[8] - x[5] * x[7] ); - check[1] = - ( x[3] * x[8] - x[5] * x[6] ); - check[2] = + ( x[3] * x[7] - x[4] * x[6] ); - // - check[3] = - ( x[1] * x[8] - x[2] * x[7] ); - check[4] = + ( x[0] * x[8] - x[2] * x[6] ); - check[5] = - ( x[0] * x[7] - x[1] * x[6] ); - // - check[6] = + ( x[1] * x[5] - x[2] * x[4] ); - check[7] = - ( x[0] * x[5] - x[2] * x[3] ); - check[8] = + ( x[0] * x[4] - x[1] * x[3] ); - // - for(size_t i = 0; i < 3 * 3; i++) - ok &= CppAD::NearEqual(check[i], g[i], eps, eps); - - return ok; - } -} -// END C++ -# endif diff --git a/ct_core/include/ct/external/cppad/speed/det_of_minor.hpp b/ct_core/include/ct/external/cppad/speed/det_of_minor.hpp deleted file mode 100644 index 2dbb4a336..000000000 --- a/ct_core/include/ct/external/cppad/speed/det_of_minor.hpp +++ /dev/null @@ -1,276 +0,0 @@ -// $Id: det_of_minor.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_DET_OF_MINOR_HPP -# define CPPAD_DET_OF_MINOR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin det_of_minor$$ -$spell - CppAD - cppad.hpp - hpp - std - Det - const - namespace -$$ - - -$section Determinant of a Minor$$ -$mindex det_of_minor matrix$$ - -$head Syntax$$ -$codei%# include -%$$ -$icode%d% = det_of_minor(%a%, %m%, %n%, %r%, %c%)%$$ - - -$head Inclusion$$ -The template function $code det_of_minor$$ is defined in the $code CppAD$$ -namespace by including -the file $code cppad/speed/det_of_minor.hpp$$ -(relative to the CppAD distribution directory). -It is only intended for example and testing purposes, -so it is not automatically included by -$cref/cppad.hpp/cppad/$$. - -$head Purpose$$ -This template function -returns the determinant of a minor of the matrix $latex A$$ -using expansion by minors. -The elements of the $latex n \times n$$ minor $latex M$$ -of the matrix $latex A$$ are defined, -for $latex i = 0 , \ldots , n-1$$ and $latex j = 0 , \ldots , n-1$$, by -$latex \[ - M_{i,j} = A_{R(i), C(j)} -\]$$ -where the functions -$latex R(i)$$ is defined by the $cref/argument r/det_of_minor/r/$$ and -$latex C(j)$$ is defined by the $cref/argument c/det_of_minor/c/$$. -$pre - -$$ -This template function -is for example and testing purposes only. -Expansion by minors is chosen as an example because it uses -a lot of floating point operations yet does not require much source code -(on the order of $icode m$$ factorial floating point operations and -about 70 lines of source code including comments). -This is not an efficient method for computing a determinant; -for example, using an LU factorization would be better. - -$head Determinant of A$$ -If the following conditions hold, the minor is the -entire matrix $latex A$$ and hence $code det_of_minor$$ -will return the determinant of $latex A$$: - -$list number$$ -$latex n = m$$. -$lnext -for $latex i = 0 , \ldots , m-1$$, $latex r[i] = i+1$$, -and $latex r[m] = 0$$. -$lnext -for $latex j = 0 , \ldots , m-1$$, $latex c[j] = j+1$$, -and $latex c[m] = 0$$. -$lend - -$head a$$ -The argument $icode a$$ has prototype -$codei% - const std::vector<%Scalar%>& %a% -%$$ -and is a vector with size $latex m * m$$ -(see description of $cref/Scalar/det_of_minor/Scalar/$$ below). -The elements of the $latex m \times m$$ matrix $latex A$$ are defined, -for $latex i = 0 , \ldots , m-1$$ and $latex j = 0 , \ldots , m-1$$, by -$latex \[ - A_{i,j} = a[ i * m + j] -\] $$ - -$head m$$ -The argument $icode m$$ has prototype -$codei% - size_t %m% -%$$ -and is the number of rows (and columns) in the square matrix $latex A$$. - -$head n$$ -The argument $icode n$$ has prototype -$codei% - size_t %n% -%$$ -and is the number of rows (and columns) in the square minor $latex M$$. - -$head r$$ -The argument $icode r$$ has prototype -$codei% - std::vector& %r% -%$$ -and is a vector with $latex m + 1$$ elements. -This vector defines the function $latex R(i)$$ -which specifies the rows of the minor $latex M$$. -To be specific, the function $latex R(i)$$ -for $latex i = 0, \ldots , n-1$$ is defined by -$latex \[ -\begin{array}{rcl} - R(0) & = & r[m] - \\ - R(i+1) & = & r[ R(i) ] -\end{array} -\] $$ -All the elements of $icode r$$ must have value -less than or equal $icode m$$. -The elements of vector $icode r$$ are modified during the computation, -and restored to their original value before the return from -$code det_of_minor$$. - -$head c$$ -The argument $icode c$$ has prototype -$codei% - std::vector& %c% -%$$ -and is a vector with $latex m + 1$$ elements -This vector defines the function $latex C(i)$$ -which specifies the rows of the minor $latex M$$. -To be specific, the function $latex C(i)$$ -for $latex j = 0, \ldots , n-1$$ is defined by -$latex \[ -\begin{array}{rcl} - C(0) & = & c[m] - \\ - C(j+1) & = & c[ C(j) ] -\end{array} -\] $$ -All the elements of $icode c$$ must have value -less than or equal $icode m$$. -The elements of vector $icode c$$ are modified during the computation, -and restored to their original value before the return from -$code det_of_minor$$. - -$head d$$ -The result $icode d$$ has prototype -$codei% - %Scalar% %d% -%$$ -and is equal to the determinant of the minor $latex M$$. - -$head Scalar$$ -If $icode x$$ and $icode y$$ are objects of type $icode Scalar$$ -and $icode i$$ is an object of type $code int$$, -the $icode Scalar$$ must support the following operations: -$table -$bold Syntax$$ - $cnext $bold Description$$ - $cnext $bold Result Type$$ -$rnext -$icode%Scalar% %x%$$ - $cnext default constructor for $icode Scalar$$ object. -$rnext -$icode%x% = %i%$$ - $cnext set value of $icode x$$ to current value of $icode i$$ -$rnext -$icode%x% = %y%$$ - $cnext set value of $icode x$$ to current value of $icode y$$ -$rnext -$icode%x% + %y%$$ - $cnext value of $icode x$$ plus $icode y$$ - $cnext $icode Scalar$$ -$rnext -$icode%x% - %y%$$ - $cnext value of $icode x$$ minus $icode y$$ - $cnext $icode Scalar$$ -$rnext -$icode%x% * %y%$$ - $cnext value of $icode x$$ times value of $icode y$$ - $cnext $icode Scalar$$ -$tend - -$children% - speed/example/det_of_minor.cpp% - omh/det_of_minor_hpp.omh -%$$ - -$head Example$$ -The file -$cref det_of_minor.cpp$$ -contains an example and test of $code det_of_minor.hpp$$. -It returns true if it succeeds and false otherwise. - -$head Source Code$$ -The file -$cref det_of_minor.hpp$$ -contains the source for this template function. - - -$end ---------------------------------------------------------------------------- -*/ -// BEGIN C++ -namespace CppAD { // BEGIN CppAD namespace -template -Scalar det_of_minor( - const std::vector& a , - size_t m , - size_t n , - std::vector& r , - std::vector& c ) -{ - const size_t R0 = r[m]; // R(0) - size_t Cj = c[m]; // C(j) (case j = 0) - size_t Cj1 = m; // C(j-1) (case j = 0) - - // check for 1 by 1 case - if( n == 1 ) return a[ R0 * m + Cj ]; - - // initialize determinant of the minor M - Scalar detM = Scalar(0); - - // initialize sign of factor for next sub-minor - int s = 1; - - // remove row with index 0 in M from all the sub-minors of M - r[m] = r[R0]; - - // for each column of M - for(size_t j = 0; j < n; j++) - { // element with index (0,j) in the minor M - Scalar M0j = a[ R0 * m + Cj ]; - - // remove column with index j in M to form next sub-minor S of M - c[Cj1] = c[Cj]; - - // compute determinant of the current sub-minor S - Scalar detS = det_of_minor(a, m, n - 1, r, c); - - // restore column Cj to representaion of M as a minor of A - c[Cj1] = Cj; - - // include this sub-minor term in the summation - if( s > 0 ) - detM = detM + M0j * detS; - else detM = detM - M0j * detS; - - // advance to next column of M - Cj1 = Cj; - Cj = c[Cj]; - s = - s; - } - - // restore row zero to the minor representation for M - r[m] = R0; - - // return the determinant of the minor M - return detM; -} -} // END CppAD namespace -// END C++ -# endif diff --git a/ct_core/include/ct/external/cppad/speed/mat_sum_sq.hpp b/ct_core/include/ct/external/cppad/speed/mat_sum_sq.hpp deleted file mode 100644 index 20fd75b29..000000000 --- a/ct_core/include/ct/external/cppad/speed/mat_sum_sq.hpp +++ /dev/null @@ -1,157 +0,0 @@ -// $Id: mat_sum_sq.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_MAT_SUM_SQ_HPP -# define CPPAD_MAT_SUM_SQ_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin mat_sum_sq$$ -$spell - sq - namespace - const - CppAD - sq - cppad.hpp -$$ - -$section Sum Elements of a Matrix Times Itself$$ -$mindex mat_sum_sq multiply speed test$$ - -$head Syntax$$ -$codei%# include -%$$ -$icode%mat_sum_sq(%n%, %x%, %y%, %z%)%$$ - -$head Purpose$$ -This routine is intended for use with the matrix multiply speed tests; -to be specific, it computes -$latex \[ -\begin{array}{rcl} - y_{i,j} & = & \sum_{k=0}^{n-1} x_{i,k} x_{k,j} - \\ - z_0 & = & \sum_{i=0}^{n-1} \sum_{j=0}^{n-1} y_{i,j} -\end{array} -\] $$ -see $cref link_mat_mul$$. - -$head Inclusion$$ -The template function $code mat_sum_sq$$ is defined in the $code CppAD$$ -namespace by including -the file $code cppad/speed/mat_sum_sq.hpp$$ -(relative to the CppAD distribution directory). -It is only intended for example and testing purposes, -so it is not automatically included by -$cref/cppad.hpp/cppad/$$. - -$head n$$ -This argument has prototype -$codei% - size_t %n% -%$$ -It specifies the size of the matrices. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -and $icode%x%.size() == %n% * %n%$$. -It contains the elements of $latex x$$ in row major order; i.e., -$latex \[ - x_{i,j} = x [ i * n + j ] -\] $$ - -$head y$$ -The argument $icode y$$ has prototype -$codei% - %Vector%& %y% -%$$ -and $icode%y%.size() == %n% * %n%$$. -The input value of its elements does not matter. -Upon return, -$latex \[ -\begin{array}{rcl} - y_{i,j} & = & \sum_{k=0}^{n-1} x_{i,k} x_{k,j} - \\ - y[ i * n + j ] & = & y_{i,j} -\end{array} -\] $$ - - -$head z$$ -The argument $icode d$$ has prototype -$codei% - %Vector%& %z% -%$$. -The input value of its element does not matter. -Upon return -$latex \[ -\begin{array}{rcl} - z_0 & = & \sum_{i=0}^{n-1} \sum_{j=0}^n y_{i,j} - \\ - z[0] & = & z_0 -\end{array} -\] $$ - -$head Vector$$ -The type $icode Vector$$ is any -$cref SimpleVector$$, or it can be a raw pointer to the vector elements. -The element type must support -addition, multiplication, and assignment to both its own type -and to a double value. - -$children% - speed/example/mat_sum_sq.cpp% - omh/mat_sum_sq_hpp.omh -%$$ - - -$head Example$$ -The file -$cref mat_sum_sq.cpp$$ -contains an example and test of $code mat_sum_sq.hpp$$. -It returns true if it succeeds and false otherwise. - -$head Source Code$$ -The file -$cref mat_sum_sq.hpp$$ -contains the source for this template function. - -$end ------------------------------------------------------------------------------- -*/ -// BEGIN C++ -# include -// -namespace CppAD { - template - void mat_sum_sq(size_t n, Vector& x , Vector& y , Vector& z) - { size_t i, j, k; - // Very simple computation of y = x * x for speed comparison - for(i = 0; i < n; i++) - { for(j = 0; j < n; j++) - { y[i * n + j] = 0.; - for(k = 0; k < n; k++) - y[i * n + j] += x[i * n + k] * x[k * n + j]; - } - } - z[0] = 0.; - for(i = 0; i < n; i++) - { for(j = 0; j < n; j++) - z[0] += y[i * n + j]; - } - return; - } - -} -// END C++ -# endif diff --git a/ct_core/include/ct/external/cppad/speed/ode_evaluate.hpp b/ct_core/include/ct/external/cppad/speed/ode_evaluate.hpp deleted file mode 100644 index fae887cb1..000000000 --- a/ct_core/include/ct/external/cppad/speed/ode_evaluate.hpp +++ /dev/null @@ -1,242 +0,0 @@ -// $Id: ode_evaluate.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_ODE_EVALUATE_HPP -# define CPPAD_ODE_EVALUATE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin ode_evaluate$$ -$spell - Runge - fabs - retaped - Jacobian - const - Cpp - cppad - hpp - fp - namespace - exp -$$ - -$section Evaluate a Function Defined in Terms of an ODE$$ -$mindex ode_evaluate$$ - - -$head Syntax$$ -$codei%# include -%$$ -$codei%ode_evaluate(%x%, %p%, %fp%)%$$ - -$head Purpose$$ -This routine evaluates a function $latex f : \B{R}^n \rightarrow \B{R}^n$$ -defined by -$latex \[ - f(x) = y(x, 1) -\] $$ -where $latex y(x, t)$$ solves the ordinary differential equation -$latex \[ -\begin{array}{rcl} - y(x, 0) & = & x - \\ - \partial_t y (x, t ) & = & g[ y(x,t) , t ] -\end{array} -\] $$ -where $latex g : \B{R}^n \times \B{R} \rightarrow \B{R}^n$$ -is an unspecified function. - -$head Inclusion$$ -The template function $code ode_evaluate$$ -is defined in the $code CppAD$$ namespace by including -the file $code cppad/speed/ode_evaluate.hpp$$ -(relative to the CppAD distribution directory). -It is only intended for example and testing purposes, -so it is not automatically included by -$cref/cppad.hpp/cppad/$$. - -$head Float$$ - -$subhead Operation Sequence$$ -The type $icode Float$$ must be a $cref NumericType$$. -The $icode Float$$ -$cref/operation sequence/glossary/Operation/Sequence/$$ -for this routine does not depend on the value of the argument $icode x$$, -hence it does not need to be retaped for each value of $latex x$$. - -$subhead fabs$$ -If $icode y$$ and $icode z$$ are $icode Float$$ objects, the syntax -$codei% - %y% = fabs(%z%) -%$$ -must be supported. Note that it does not matter if the operation -sequence for $code fabs$$ depends on $icode z$$ because the -corresponding results are not actually used by $code ode_evaluate$$; -see $code fabs$$ in $cref/Runge45/Runge45/Scalar/fabs/$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const CppAD::vector<%Float%>& %x% -%$$ -It contains he argument value for which the function, -or its derivative, is being evaluated. -The value $latex n$$ is determined by the size of the vector $icode x$$. - -$head p$$ -The argument $icode p$$ has prototype -$codei% - size_t %p% -%$$ - -$subhead p == 0$$ -In this case a numerical method is used to solve the ode -and obtain an accurate approximation for $latex y(x, 1)$$. -This numerical method has a fixed -that does not depend on $icode x$$. - -$subhead p = 1$$ -In this case an analytic solution for the partial derivative -$latex \partial_x y(x, 1)$$ is returned. - -$head fp$$ -The argument $icode fp$$ has prototype -$codei% - CppAD::vector<%Float%>& %fp% -%$$ -The input value of the elements of $icode fp$$ does not matter. - -$subhead Function$$ -If $icode p$$ is zero, $icode fp$$ has size equal to $latex n$$ -and contains the value of $latex y(x, 1)$$. - -$subhead Gradient$$ -If $icode p$$ is one, $icode fp$$ has size equal to $icode n^2$$ -and for $latex i = 0 , \ldots and n-1$$, $latex j = 0 , \ldots , n-1$$ -$latex \[ - \D{y[i]}{x[j]} (x, 1) = fp [ i \cdot n + j ] -\] $$ - -$children% - speed/example/ode_evaluate.cpp% - omh/ode_evaluate.omh -%$$ - -$head Example$$ -The file -$cref ode_evaluate.cpp$$ -contains an example and test of $code ode_evaluate.hpp$$. -It returns true if it succeeds and false otherwise. - - -$head Source Code$$ -The file -$cref ode_evaluate.hpp$$ -contains the source code for this template function. - -$end -*/ -// BEGIN C++ -# include -# include -# include - -namespace CppAD { - - template - class ode_evaluate_fun { - public: - // Given that y_i (0) = x_i, - // the following y_i (t) satisfy the ODE below: - // y_0 (t) = x[0] - // y_1 (t) = x[1] + x[0] * t - // y_2 (t) = x[2] + x[1] * t + x[0] * t^2/2 - // y_3 (t) = x[3] + x[2] * t + x[1] * t^2/2 + x[0] * t^3 / 3! - // ... - void Ode( - const Float& t, - const CppAD::vector& y, - CppAD::vector& f) - { size_t n = y.size(); - f[0] = 0.; - for(size_t k = 1; k < n; k++) - f[k] = y[k-1]; - } - }; - // - template - void ode_evaluate( - const CppAD::vector& x , - size_t p , - CppAD::vector& fp ) - { using CppAD::vector; - typedef vector VectorFloat; - - size_t n = x.size(); - CPPAD_ASSERT_KNOWN( p == 0 || p == 1, - "ode_evaluate: p is not zero or one" - ); - CPPAD_ASSERT_KNOWN( - ((p==0) & (fp.size()==n)) || ((p==1) & (fp.size()==n*n)), - "ode_evaluate: the size of fp is not correct" - ); - if( p == 0 ) - { // function that defines the ode - ode_evaluate_fun F; - - // number of Runge45 steps to use - size_t M = 10; - - // initial and final time - Float ti = 0.0; - Float tf = 1.0; - - // initial value for y(x, t); i.e. y(x, 0) - // (is a reference to x) - const VectorFloat& yi = x; - - // final value for y(x, t); i.e., y(x, 1) - // (is a reference to fp) - VectorFloat& yf = fp; - - // Use fourth order Runge-Kutta to solve ODE - yf = CppAD::Runge45(F, M, ti, tf, yi); - - return; - } - /* Compute derivaitve of y(x, 1) w.r.t x - y_0 (x, t) = x[0] - y_1 (x, t) = x[1] + x[0] * t - y_2 (x, t) = x[2] + x[1] * t + x[0] * t^2/2 - y_3 (x, t) = x[3] + x[2] * t + x[1] * t^2/2 + x[0] * t^3 / 3! - ... - */ - size_t i, j, k; - for(i = 0; i < n; i++) - { for(j = 0; j < n; j++) - fp[ i * n + j ] = 0.0; - } - size_t factorial = 1; - for(k = 0; k < n; k++) - { if( k > 1 ) - factorial *= k; - for(i = k; i < n; i++) - { // partial w.r.t x[i-k] of x[i-k] * t^k / k! - j = i - k; - fp[ i * n + j ] += 1.0 / Float(factorial); - } - } - } -} -// END C++ - -# endif diff --git a/ct_core/include/ct/external/cppad/speed/sparse_hes_fun.hpp b/ct_core/include/ct/external/cppad/speed/sparse_hes_fun.hpp deleted file mode 100644 index fb8775d7f..000000000 --- a/ct_core/include/ct/external/cppad/speed/sparse_hes_fun.hpp +++ /dev/null @@ -1,268 +0,0 @@ -// $Id: sparse_hes_fun.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SPARSE_HES_FUN_HPP -# define CPPAD_SPARSE_HES_FUN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin sparse_hes_fun$$ -$spell - hes - cppad - hpp - fp - CppAD - namespace - const - bool - exp - arg -$$ - -$section Evaluate a Function That Has a Sparse Hessian$$ -$mindex sparse_hes_fun$$ - - -$head Syntax$$ -$codei%# include -%$$ -$codei%sparse_hes_fun(%n%, %x%, %row%, %col%, %p%, %fp%)%$$ - -$head Purpose$$ -This routine evaluates -$latex f(x)$$, $latex f^{(1)} (x)$$, or $latex f^{(2)} (x)$$ -where the Hessian $latex f^{(2)} (x)$$ is sparse. -The function $latex f : \B{R}^n \rightarrow \B{R}$$ only depends on the -size and contents of the index vectors $icode row$$ and $icode col$$. -The non-zero entries in the Hessian of this function have -one of the following forms: -$latex \[ - \DD{f}{x[row[k]]}{x[row[k]]} - \; , \; - \DD{f}{x[row[k]]}{x[col[k]]} - \; , \; - \DD{f}{x[col[k]]}{x[row[k]]} - \; , \; - \DD{f}{x[col[k]]}{x[col[k]]} -\] $$ -for some $latex k $$ between zero and $latex K-1 $$. -All the other terms of the Hessian are zero. - -$head Inclusion$$ -The template function $code sparse_hes_fun$$ -is defined in the $code CppAD$$ namespace by including -the file $code cppad/speed/sparse_hes_fun.hpp$$ -(relative to the CppAD distribution directory). -It is only intended for example and testing purposes, -so it is not automatically included by -$cref/cppad.hpp/cppad/$$. - -$head Float$$ -The type $icode Float$$ must be a $cref NumericType$$. -In addition, if $icode y$$ and $icode z$$ are $icode Float$$ objects, -$codei% - %y% = exp(%z%) -%$$ -must set the $icode y$$ equal the exponential of $icode z$$, i.e., -the derivative of $icode y$$ with respect to $icode z$$ is equal to $icode y$$. - -$head FloatVector$$ -The type $icode FloatVector$$ is any -$cref SimpleVector$$, or it can be a raw pointer, -with elements of type $icode Float$$. - -$head n$$ -The argument $icode n$$ has prototype -$codei% - size_t %n% -%$$ -It specifies the dimension for the domain space for $latex f(x)$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %FloatVector%& %x% -%$$ -It contains the argument value for which the function, -or its derivative, is being evaluated. -We use $latex n$$ to denote the size of the vector $icode x$$. - -$head row$$ -The argument $icode row$$ has prototype -$codei% - const CppAD::vector& %row% -%$$ -It specifies one of the first -index of $latex x$$ for each non-zero Hessian term -(see $cref/purpose/sparse_hes_fun/Purpose/$$ above). -All the elements of $icode row$$ must be between zero and $icode%n%-1%$$. -The value $latex K$$ is defined by $icode%K% = %row%.size()%$$. - -$head col$$ -The argument $icode col$$ has prototype -$codei% - const CppAD::vector& %col% -%$$ -and its size must be $latex K$$; i.e., the same as for $icode col$$. -It specifies the second -index of $latex x$$ for the non-zero Hessian terms. -All the elements of $icode col$$ must be between zero and $icode%n%-1%$$. -There are no duplicated entries requested, to be specific, -if $icode%k1% != %k2%$$ then -$codei% - ( %row%[%k1%] , %col%[%k1%] ) != ( %row%[%k2%] , %col%[%k2%] ) -%$$ - -$head p$$ -The argument $icode p$$ has prototype -$codei% - size_t %p% -%$$ -It is either zero or two and -specifies the order of the derivative of $latex f$$ -that is being evaluated, i.e., $latex f^{(p)} (x)$$ is evaluated. - -$head fp$$ -The argument $icode fp$$ has prototype -$codei% - %FloatVector%& %fp% -%$$ -The input value of the elements of $icode fp$$ does not matter. - -$subhead Function$$ -If $icode p$$ is zero, $icode fp$$ has size one and -$icode%fp%[0]%$$ is the value of $latex f(x)$$. - -$subhead Hessian$$ -If $icode p$$ is two, $icode fp$$ has size $icode K$$ and -for $latex k = 0 , \ldots , K-1$$, -$latex \[ - \DD{f}{ x[ \R{row}[k] ] }{ x[ \R{col}[k] ]} = fp [k] -\] $$ - -$children% - speed/example/sparse_hes_fun.cpp% - omh/sparse_hes_fun.omh -%$$ - -$head Example$$ -The file -$cref sparse_hes_fun.cpp$$ -contains an example and test of $code sparse_hes_fun.hpp$$. -It returns true if it succeeds and false otherwise. - -$head Source Code$$ -The file -$cref sparse_hes_fun.hpp$$ -contains the source code for this template function. - -$end ------------------------------------------------------------------------------- -*/ -// BEGIN C++ -# include -# include -# include - -// following needed by gcc under fedora 17 so that exp(double) is defined -# include - -namespace CppAD { - template - void sparse_hes_fun( - size_t n , - const FloatVector& x , - const CppAD::vector& row , - const CppAD::vector& col , - size_t p , - FloatVector& fp ) - { - // check numeric type specifications - CheckNumericType(); - - // check value of p - CPPAD_ASSERT_KNOWN( - p == 0 || p == 2, - "sparse_hes_fun: p != 0 and p != 2" - ); - - size_t K = row.size(); - size_t i, j, k; - if( p == 0 ) - fp[0] = Float(0); - else - { for(k = 0; k < K; k++) - fp[k] = Float(0); - } - - // determine which diagonal entries are present in row[k], col[k] - CppAD::vector diagonal(n); - for(i = 0; i < n; i++) - diagonal[i] = K; // no diagonal entry for this row - for(k = 0; k < K; k++) - { if( row[k] == col[k] ) - { CPPAD_ASSERT_UNKNOWN( diagonal[row[k]] == K ); - // index of the diagonal entry - diagonal[ row[k] ] = k; - } - } - - // determine which entries must be multiplied by a factor of two - CppAD::vector factor(K); - for(k = 0; k < K; k++) - { factor[k] = Float(1); - for(size_t k1 = 0; k1 < K; k1++) - { bool reflected = true; - reflected &= k != k1; - reflected &= row[k] != col[k]; - reflected &= row[k] == col[k1]; - reflected &= col[k] == row[k1]; - if( reflected ) - factor[k] = Float(2); - } - } - - Float t; - for(k = 0; k < K; k++) - { i = row[k]; - j = col[k]; - t = exp( x[i] * x[j] ); - switch(p) - { - case 0: - fp[0] += t; - break; - - case 2: - if( i == j ) - { // dt_dxi = 2.0 * xi * t - fp[k] += ( Float(2) + Float(4) * x[i] * x[i] ) * t; - } - else - { // dt_dxi = xj * t - fp[k] += factor[k] * ( Float(1) + x[i] * x[j] ) * t; - if( diagonal[i] != K ) - { size_t ki = diagonal[i]; - fp[ki] += x[j] * x[j] * t; - } - if( diagonal[j] != K ) - { size_t kj = diagonal[j]; - fp[kj] += x[i] * x[i] * t; - } - } - break; - } - } - - } -} -// END C++ -# endif diff --git a/ct_core/include/ct/external/cppad/speed/sparse_jac_fun.hpp b/ct_core/include/ct/external/cppad/speed/sparse_jac_fun.hpp deleted file mode 100644 index f8ea524e2..000000000 --- a/ct_core/include/ct/external/cppad/speed/sparse_jac_fun.hpp +++ /dev/null @@ -1,225 +0,0 @@ -// $Id: sparse_jac_fun.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_SPARSE_JAC_FUN_HPP -# define CPPAD_SPARSE_JAC_FUN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin sparse_jac_fun$$ -$spell - Jacobian - jac - cppad - hpp - fp - CppAD - namespace - const - bool - exp - arg -$$ - -$section Evaluate a Function That Has a Sparse Jacobian$$ -$mindex sparse_jac_fun$$ - - -$head Syntax$$ -$codei%# include -%$$ -$codei%sparse_jac_fun(%m%, %n%, %x%, %row%, %col%, %p%, %fp%)%$$ - -$head Purpose$$ -This routine evaluates -$latex f(x)$$ and $latex f^{(1)} (x)$$ -where the Jacobian $latex f^{(1)} (x)$$ is sparse. -The function $latex f : \B{R}^n \rightarrow \B{R}^m$$ only depends on the -size and contents of the index vectors $icode row$$ and $icode col$$. -The non-zero entries in the Jacobian of this function have -one of the following forms: -$latex \[ - \D{ f[row[k]]}{x[col[k]]} -\] $$ -for some $latex k $$ between zero and $latex K-1$$. -All the other terms of the Jacobian are zero. - -$head Inclusion$$ -The template function $code sparse_jac_fun$$ -is defined in the $code CppAD$$ namespace by including -the file $code cppad/speed/sparse_jac_fun.hpp$$ -(relative to the CppAD distribution directory). -It is only intended for example and testing purposes, -so it is not automatically included by -$cref/cppad.hpp/cppad/$$. - -$head Float$$ -The type $icode Float$$ must be a $cref NumericType$$. -In addition, if $icode y$$ and $icode z$$ are $icode Float$$ objects, -$codei% - %y% = exp(%z%) -%$$ -must set the $icode y$$ equal the exponential of $icode z$$, i.e., -the derivative of $icode y$$ with respect to $icode z$$ is equal to $icode y$$. - -$head FloatVector$$ -The type $icode FloatVector$$ is any -$cref SimpleVector$$, or it can be a raw pointer, -with elements of type $icode Float$$. - -$head n$$ -The argument $icode n$$ has prototype -$codei% - size_t %n% -%$$ -It specifies the dimension for the domain space for $latex f(x)$$. - -$head m$$ -The argument $icode m$$ has prototype -$codei% - size_t %m% -%$$ -It specifies the dimension for the range space for $latex f(x)$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %FloatVector%& %x% -%$$ -It contains the argument value for which the function, -or its derivative, is being evaluated. -We use $latex n$$ to denote the size of the vector $icode x$$. - -$head row$$ -The argument $icode row$$ has prototype -$codei% - const CppAD::vector& %row% -%$$ -It specifies indices in the range of $latex f(x)$$ for non-zero components -of the Jacobian -(see $cref/purpose/sparse_hes_fun/Purpose/$$ above). -The value $latex K$$ is defined by $icode%K% = %row%.size()%$$. -All the elements of $icode row$$ must be between zero and $icode%m%-1%$$. - -$head col$$ -The argument $icode row$$ has prototype -$codei% - const CppAD::vector& %col% -%$$ -and its size must be $latex K$$; i.e., the same as for $icode col$$. -It specifies the component of $latex x$$ for -the non-zero Jacobian terms. -All the elements of $icode col$$ must be between zero and $icode%n%-1%$$. - -$head p$$ -The argument $icode p$$ has prototype -$codei% - size_t %p% -%$$ -It is either zero or one and -specifies the order of the derivative of $latex f$$ -that is being evaluated, i.e., $latex f^{(p)} (x)$$ is evaluated. - -$head fp$$ -The argument $icode fp$$ has prototype -$codei% - %FloatVector%& %fp% -%$$ -If $icode%p% = 0%$$, it size is $icode m$$ -otherwise its size is $icode K$$. -The input value of the elements of $icode fp$$ does not matter. - -$subhead Function$$ -If $icode p$$ is zero, $icode fp$$ has size $latex m$$ and -$codei%(%fp%[0]%, ... , %fp%[%m%-1])%$$ is the value of $latex f(x)$$. - -$subhead Jacobian$$ -If $icode p$$ is one, $icode fp$$ has size $icode K$$ and -for $latex k = 0 , \ldots , K-1$$, -$latex \[ - \D{f[ \R{row}[i] ]}{x[ \R{col}[j] ]} = fp [k] -\] $$ - -$children% - speed/example/sparse_jac_fun.cpp% - omh/sparse_jac_fun.omh -%$$ - -$head Example$$ -The file -$cref sparse_jac_fun.cpp$$ -contains an example and test of $code sparse_jac_fun.hpp$$. -It returns true if it succeeds and false otherwise. - -$head Source Code$$ -The file -$cref sparse_jac_fun.hpp$$ -contains the source code for this template function. - -$end ------------------------------------------------------------------------------- -*/ -// BEGIN C++ -# include -# include -# include - -// following needed by gcc under fedora 17 so that exp(double) is defined -# include - -namespace CppAD { - template - void sparse_jac_fun( - size_t m , - size_t n , - const FloatVector& x , - const CppAD::vector& row , - const CppAD::vector& col , - size_t p , - FloatVector& fp ) - { - // check numeric type specifications - CheckNumericType(); - // check value of p - CPPAD_ASSERT_KNOWN( - p == 0 || p == 1, - "sparse_jac_fun: p != 0 and p != 1" - ); - size_t K = row.size(); - CPPAD_ASSERT_KNOWN( - K >= m, - "sparse_jac_fun: row.size() < m" - ); - size_t i, j, k; - - if( p == 0 ) - for(i = 0; i < m; i++) - fp[i] = Float(0); - - Float t; - for(k = 0; k < K; k++) - { i = row[k]; - j = col[k]; - t = exp( x[j] * x[j] / 2.0 ); - switch(p) - { - case 0: - fp[i] += t; - break; - - case 1: - fp[k] = t * x[j]; - break; - } - } - } -} -// END C++ -# endif diff --git a/ct_core/include/ct/external/cppad/speed/uniform_01.hpp b/ct_core/include/ct/external/cppad/speed/uniform_01.hpp deleted file mode 100644 index 537b9eff3..000000000 --- a/ct_core/include/ct/external/cppad/speed/uniform_01.hpp +++ /dev/null @@ -1,107 +0,0 @@ -// $Id: uniform_01.hpp 3757 2015-11-30 12:03:07Z bradbell $ -# ifndef CPPAD_UNIFORM_01_HPP -# define CPPAD_UNIFORM_01_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin uniform_01$$ -$spell - CppAD - cppad.hpp - namespace -$$ - -$section Simulate a [0,1] Uniform Random Variate$$ -$mindex uniform_01$$ - - -$head Syntax$$ -$codei%# include -%$$ -$codei%uniform_01(%seed%) -%$$ -$codei%uniform_01(%n%, %x%)%$$ - -$head Purpose$$ -This routine is used to create random values for speed testing purposes. - -$head Inclusion$$ -The template function $code uniform_01$$ is defined in the $code CppAD$$ -namespace by including -the file $code cppad/speed/uniform_01.hpp$$ -(relative to the CppAD distribution directory). -It is only intended for example and testing purposes, -so it is not automatically included by -$cref/cppad.hpp/cppad/$$. - -$head seed$$ -The argument $icode seed$$ has prototype -$codei% - size_t %seed% -%$$ -It specifies a seed -for the uniform random number generator. - -$head n$$ -The argument $icode n$$ has prototype -$codei% - size_t %n% -%$$ -It specifies the number of elements in the random vector $icode x$$. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - %Vector% &%x% -%$$. -The input value of the elements of $icode x$$ does not matter. -Upon return, the elements of $icode x$$ are set to values -randomly sampled over the interval [0,1]. - -$head Vector$$ -If $icode y$$ is a $code double$$ value, -the object $icode x$$ must support the syntax -$codei% - %x%[%i%] = %y% -%$$ -where $icode i$$ has type $code size_t$$ with value less than -or equal $latex n-1$$. -This is the only requirement of the type $icode Vector$$. - -$children% - omh/uniform_01_hpp.omh -%$$ - -$head Source Code$$ -The file -$cref uniform_01.hpp$$ -constraints the source code for this template function. - -$end ------------------------------------------------------------------------------- -*/ -// BEGIN C++ -# include - -namespace CppAD { - inline void uniform_01(size_t seed) - { std::srand( (unsigned int) seed); } - - template - void uniform_01(size_t n, Vector &x) - { static double factor = 1. / double(RAND_MAX); - while(n--) - x[n] = std::rand() * factor; - } -} -// END C++ -# endif diff --git a/ct_core/include/ct/external/cppad/utility.hpp b/ct_core/include/ct/external/cppad/utility.hpp deleted file mode 100644 index b046fe2fc..000000000 --- a/ct_core/include/ct/external/cppad/utility.hpp +++ /dev/null @@ -1,41 +0,0 @@ -// $Id$ -# ifndef CPPAD_UTILITY_HPP -# define CPPAD_UTILITY_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# include -# endif diff --git a/ct_core/include/ct/external/cppad/utility/check_numeric_type.hpp b/ct_core/include/ct/external/cppad/utility/check_numeric_type.hpp deleted file mode 100644 index b9bd0e19f..000000000 --- a/ct_core/include/ct/external/cppad/utility/check_numeric_type.hpp +++ /dev/null @@ -1,176 +0,0 @@ -// $Id: check_numeric_type.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_CHECK_NUMERIC_TYPE_HPP -# define CPPAD_CHECK_NUMERIC_TYPE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin CheckNumericType$$ -$spell - alloc - cppad.hpp - CppAD -$$ - -$section Check NumericType Class Concept$$ -$mindex numeric CheckNumericType$$ - - -$head Syntax$$ -$codei%# include -%$$ -$codei%CheckNumericType<%NumericType%>()%$$ - - -$head Purpose$$ -The syntax -$codei% - CheckNumericType<%NumericType%>() -%$$ -preforms compile and run time checks that the type specified -by $icode NumericType$$ satisfies all the requirements for -a $cref NumericType$$ class. -If a requirement is not satisfied, -a an error message makes it clear what condition is not satisfied. - -$head Include$$ -The file $code cppad/check_numeric_type.hpp$$ is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest -if the CppAD include files. - -$head Parallel Mode$$ -The routine $cref/thread_alloc::parallel_setup/ta_parallel_setup/$$ -must be called before it -can be used in $cref/parallel/ta_in_parallel/$$ mode. - -$head Example$$ -$children% - example/check_numeric_type.cpp -%$$ -The file $cref check_numeric_type.cpp$$ -contains an example and test of this function. -It returns true, if it succeeds an false otherwise. -The comments in this example suggest a way to change the example -so an error message occurs. - -$end ---------------------------------------------------------------------------- -*/ - -# include -# include - -namespace CppAD { - -# ifdef NDEBUG - template - void CheckNumericType(void) - { } -# else - template - NumericType CheckNumericType(void) - { // Section 3.6.2 of ISO/IEC 14882:1998(E) states: "The storage for - // objects with static storage duration (3.7.1) shall be zero- - // initialized (8.5) before any other initialization takes place." - static size_t count[CPPAD_MAX_NUM_THREADS]; - size_t thread = thread_alloc::thread_num(); - if( count[thread] > 0 ) - return NumericType(0); - count[thread]++; - /* - contructors - */ - NumericType check_NumericType_default_constructor; - NumericType check_NumericType_constructor_from_int(1); - - const NumericType x(1); - - NumericType check_NumericType_copy_constructor(x); - - // assignment - NumericType check_NumericType_assignment; - check_NumericType_assignment = x; - - /* - unary operators - */ - const NumericType check_NumericType_unary_plus(1); - NumericType check_NumericType_unary_plus_result = - + check_NumericType_unary_plus; - - const NumericType check_NumericType_unary_minus(1); - NumericType check_NumericType_unary_minus_result = - - check_NumericType_unary_minus; - - /* - binary operators - */ - const NumericType check_NumericType_binary_addition(1); - NumericType check_NumericType_binary_addition_result = - check_NumericType_binary_addition + x; - - const NumericType check_NumericType_binary_subtraction(1); - NumericType check_NumericType_binary_subtraction_result = - check_NumericType_binary_subtraction - x; - - const NumericType check_NumericType_binary_multiplication(1); - NumericType check_NumericType_binary_multiplication_result = - check_NumericType_binary_multiplication * x; - - const NumericType check_NumericType_binary_division(1); - NumericType check_NumericType_binary_division_result = - check_NumericType_binary_division / x; - - /* - computed assignment operators - */ - NumericType - check_NumericType_computed_assignment_addition(1); - check_NumericType_computed_assignment_addition += x; - - NumericType - check_NumericType_computed_assignment_subtraction(1); - check_NumericType_computed_assignment_subtraction -= x; - - NumericType - check_NumericType_computed_assignment_multiplication(1); - check_NumericType_computed_assignment_multiplication *= x; - - NumericType - check_NumericType_computed_assignment_division(1); - check_NumericType_computed_assignment_division /= x; - - /* - use all values so as to avoid warnings - */ - check_NumericType_default_constructor = x; - return - + check_NumericType_default_constructor - + check_NumericType_constructor_from_int - + check_NumericType_copy_constructor - + check_NumericType_assignment - + check_NumericType_unary_plus_result - + check_NumericType_unary_minus_result - + check_NumericType_binary_addition_result - + check_NumericType_binary_subtraction_result - + check_NumericType_binary_multiplication_result - + check_NumericType_binary_division_result - + check_NumericType_computed_assignment_addition - + check_NumericType_computed_assignment_subtraction - + check_NumericType_computed_assignment_multiplication - + check_NumericType_computed_assignment_division - ; - } -# endif - -} // end namespace CppAD - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/check_simple_vector.hpp b/ct_core/include/ct/external/cppad/utility/check_simple_vector.hpp deleted file mode 100644 index d956093d6..000000000 --- a/ct_core/include/ct/external/cppad/utility/check_simple_vector.hpp +++ /dev/null @@ -1,201 +0,0 @@ -// $Id: check_simple_vector.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_CHECK_SIMPLE_VECTOR_HPP -# define CPPAD_CHECK_SIMPLE_VECTOR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin CheckSimpleVector$$ -$spell - alloc - const - cppad.hpp - CppAD -$$ - -$section Check Simple Vector Concept$$ -$mindex CheckSimpleVector$$ - - -$head Syntax$$ -$codei%# include -%$$ -$codei%CheckSimpleVector<%Scalar%, %Vector%>()%$$ -$pre -$$ -$codei%CheckSimpleVector<%Scalar%, %Vector%>(%x%, %y%)%$$ - - -$head Purpose$$ -Preforms compile and run time checks that the type specified -by $icode Vector$$ satisfies all the requirements for -a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Scalar$$. -If a requirement is not satisfied, -a an error message makes it clear what condition is not satisfied. - -$head x, y$$ -If the arguments $icode x$$ and $icode y$$ are present, -they have prototype -$codei% - const %Scalar%& %x% - const %Scalar%& %y% -%$$ -In addition, the check -$codei% - %x% == %x% -%$$ -will return the boolean value $code true$$, and -$codei% - %x% == %y% -%$$ -will return $code false$$. - -$head Restrictions$$ -If the arguments $icode x$$ and $icode y$$ are not present, -the following extra assumption is made by $code CheckSimpleVector$$: -If $icode x$$ is a $icode Scalar$$ object -$codei% - %x% = 0 - %y% = 1 -%$$ -assigns values to the objects $icode x$$ and $icode y$$. -In addition, -$icode%x% == %x%$$ would return the boolean value $code true$$ and -$icode%x% == %y%$$ would return $code false$$. - -$head Include$$ -The file $code cppad/check_simple_vector.hpp$$ is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest -if the CppAD include files. - -$head Parallel Mode$$ -The routine $cref/thread_alloc::parallel_setup/ta_parallel_setup/$$ -must be called before it -can be used in $cref/parallel/ta_in_parallel/$$ mode. - -$head Example$$ -$children% - example/check_simple_vector.cpp -%$$ -The file $cref check_simple_vector.cpp$$ -contains an example and test of this function where $icode S$$ -is the same as $icode T$$. -It returns true, if it succeeds an false otherwise. -The comments in this example suggest a way to change the example -so $icode S$$ is not the same as $icode T$$. - -$end ---------------------------------------------------------------------------- -*/ - -# include -# include -# include -# include - -namespace CppAD { - -# ifdef NDEBUG - template - inline void CheckSimpleVector(const Scalar& x, const Scalar& y) - { } - template - inline void CheckSimpleVector(void) - { } -# else - template - struct ok_if_S_same_as_T { }; - - template - struct ok_if_S_same_as_T { T value; }; - - template - void CheckSimpleVector(const Scalar& x, const Scalar& y) - { CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL - static size_t count; - if( count > 0 ) - return; - count++; - - // value_type must be type of elements of Vector - typedef typename Vector::value_type value_type; - - // check that elements of Vector have type Scalar - struct ok_if_S_same_as_T x_copy; - x_copy.value = x; - - // check default constructor - Vector d; - - // size member function - CPPAD_ASSERT_KNOWN( - d.size() == 0, - "default construtor result does not have size zero" - ); - - // resize to same size as other vectors in test - d.resize(1); - - // check sizing constructor - Vector s(1); - - // check element assignment - s[0] = y; - CPPAD_ASSERT_KNOWN( - s[0] == y, - "element assignment failed" - ); - - // check copy constructor - s[0] = x_copy.value; - const Vector c(s); - s[0] = y; - CPPAD_ASSERT_KNOWN( - c[0] == x, - "copy constructor is shallow" - ); - - // vector assignment operator - d[0] = x; - s = d; - s[0] = y; - CPPAD_ASSERT_KNOWN( - d[0] == x, - "assignment operator is shallow" - ); - - // element access, right side const - // element assignment, left side not const - d[0] = c[0]; - CPPAD_ASSERT_KNOWN( - d[0] == x, - "element assignment from const failed" - ); - } - template - void CheckSimpleVector(void) - { Scalar x; - Scalar y; - - // use assignment and not constructor - x = 0; - y = 1; - - CheckSimpleVector(x, y); - } - -# endif - -} // end namespace CppAD - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/elapsed_seconds.hpp b/ct_core/include/ct/external/cppad/utility/elapsed_seconds.hpp deleted file mode 100644 index d74cc95bd..000000000 --- a/ct_core/include/ct/external/cppad/utility/elapsed_seconds.hpp +++ /dev/null @@ -1,175 +0,0 @@ -// $Id: elapsed_seconds.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_ELAPSED_SECONDS_HPP -# define CPPAD_ELAPSED_SECONDS_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin elapsed_seconds$$ -$spell - cppad.hpp - Microsoft - gettimeofday - std - chrono -$$ - -$section Returns Elapsed Number of Seconds$$ -$mindex elapsed_seconds time$$ - - -$head Syntax$$ -$codei%# include -%$$ -$icode%s% = elapsed_seconds()%$$ - -$head Purpose$$ -This routine is accurate to within .02 seconds -(see $cref elapsed_seconds.cpp$$). -It does not necessary work for time intervals that are greater than a day. -$list number$$ -If the C++11 $code std::chrono::high_resolution_clock$$ is available, -it will be used for timing. -$lnext -Otherwise, if running under the Microsoft compiler, -$code ::GetSystemTime$$ will be used for timing. -$lnext -Otherwise, if $code gettimeofday$$ is available, it is used for timing. -$lnext -Otherwise, $code std::clock()$$ will be used for timing. -$lend - -$head s$$ -is a $code double$$ equal to the -number of seconds since the first call to $code elapsed_seconds$$. - -$head Microsoft Systems$$ -It you are using $code ::GetSystemTime$$, -you will need to link in the external routine -called $cref microsoft_timer$$. - -$children% - speed/example/elapsed_seconds.cpp -%$$ -$head Example$$ -The routine $cref elapsed_seconds.cpp$$ is -an example and test of this routine. - - -$end ------------------------------------------------------------------------ -*/ - -// For some unknown reason under Fedora (which needs to be understood), -// if you move this include for cppad_assert.hpp below include for define.hpp, -// cd work/speed/example -// make test.sh -// fails with the error message 'gettimeofday' not defined. -# include - -// define CPPAD_NULL -# include - -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -# if CPPAD_USE_CPLUSPLUS_2011 -# include -# elif _MSC_VER -extern double microsoft_timer(void); -# elif CPPAD_HAS_GETTIMEOFDAY -# include -# else -# include -# endif - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file elapsed_seconds.hpp -\brief Function that returns the elapsed seconds from first call. -*/ - -/*! -Returns the elapsed number since the first call to this function. - -This routine tries is accurate to within .02 seconds. -It does not necessary work for time intervals that are less than a day. -\li -If running under the Microsoft system, it uses \c ::%GetSystemTime for timing. -\li -Otherwise, if \c gettimeofday is available, it is used. -\li -Otherwise, \c std::clock() is used. - -\return -The number of seconds since the first call to \c elapsed_seconds. -*/ -inline double elapsed_seconds(void) -// -------------------------------------------------------------------------- -# if CPPAD_USE_CPLUSPLUS_2011 -{ CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static bool first_ = true; - static std::chrono::time_point start_; - if( first_ ) - { start_ = std::chrono::high_resolution_clock::now(); - first_ = false; - return 0.0; - } - std::chrono::time_point now; - now = std::chrono::high_resolution_clock::now(); - std::chrono::duration difference = now - start_; - return difference.count(); -} -// -------------------------------------------------------------------------- -# elif _MSC_VER -{ return microsoft_timer(); } -// -------------------------------------------------------------------------- -# elif CPPAD_HAS_GETTIMEOFDAY -{ CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static bool first_ = true; - static struct timeval tv_; - struct timeval tv; - if( first_ ) - { gettimeofday(&tv_, CPPAD_NULL); - first_ = false; - return 0.; - } - gettimeofday(&tv, CPPAD_NULL); - assert( tv.tv_sec >= tv_.tv_sec ); - - double sec = double(tv.tv_sec - tv_.tv_sec); - double usec = double(tv.tv_usec) - double(tv_.tv_usec); - double diff = sec + 1e-6*usec; - - return diff; -} -// -------------------------------------------------------------------------- -# else // Not CPPAD_USE_CPLUSPLUS_2011 or CPPAD_HAS_GETTIMEOFDAY -{ CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static bool first_ = true; - static double tic_; - double tic; - if( first_ ) - { tic_ = double(std::clock()); - first_ = false; - return 0.; - } - tic = double( std::clock() ); - - double diff = (tic - tic_) / double(CLOCKS_PER_SEC); - - return diff; -} -# endif -// -------------------------------------------------------------------------- -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/utility/error_handler.hpp b/ct_core/include/ct/external/cppad/utility/error_handler.hpp deleted file mode 100644 index 9ec3aac7f..000000000 --- a/ct_core/include/ct/external/cppad/utility/error_handler.hpp +++ /dev/null @@ -1,236 +0,0 @@ -// $Id: error_handler.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_ERROR_HANDLER_HPP -# define CPPAD_ERROR_HANDLER_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin ErrorHandler$$ -$spell - cppad.hpp - CppAD - exp - bool - const -$$ - -$section Replacing the CppAD Error Handler$$ -$mindex replace assert exception ErrorHandler$$ - -$head Syntax$$ -$codei%# include -%$$ -$codei%ErrorHandler %info%(%handler%) -%$$ -$codei%ErrorHandler::Call(%known%, %line%, %file%, %exp%, %msg%) -%$$ - -$head Constructor$$ -When you construct a $code ErrorHandler$$ object, -the current CppAD error handler is replaced by $icode handler$$. -When the object is destructed, the previous CppAD error handler is restored. - -$subhead Parallel Mode$$ -The $code ErrorHandler$$ constructor and destructor cannot be called in -$cref/parallel/ta_in_parallel/$$ execution mode. -Furthermore, this rule is not abided by, a raw C++ $code assert$$, -instead of one that uses this error handler, will be generated. - -$head Call$$ -When $code ErrorHandler::Call$$ is called, -the current CppAD error handler is used to report an error. -This starts out as a default error handler and can be replaced -using the $code ErrorHandler$$ constructor. - -$head info$$ -The object $icode info$$ is used to store information -that is necessary to restore the previous CppAD error handler. -This is done when the destructor for $icode info$$ is called. - - -$head handler$$ -The argument $icode handler$$ has prototype -$codei% - void (*%handler%) - (bool, int, const char *, const char *, const char *); -%$$ -When an error is detected, -it is called with the syntax -$codei% - %handler% (%known%, %line%, %file%, %exp%, %msg%) -%$$ -This routine should not return; i.e., upon detection of the error, -the routine calling $icode handler$$ does not know how to proceed. - -$head known$$ -The $icode handler$$ argument $icode known$$ has prototype -$codei% - bool %known% -%$$ -If it is true, the error being reported is from a know problem. - -$head line$$ -The $icode handler$$ argument $icode line$$ has prototype -$codei% - int %line% -%$$ -It reports the source code line number where the error is detected. - -$head file$$ -The $icode handler$$ argument $icode file$$ has prototype -$codei% - const char *%file% -%$$ -and is a $code '\0'$$ terminated character vector. -It reports the source code file where the error is detected. - -$head exp$$ -The $icode handler$$ argument $icode exp$$ has prototype -$codei% - const char *%exp% -%$$ -and is a $code '\0'$$ terminated character vector. -It is a source code boolean expression that should have been true, -but is false, -and thereby causes this call to $icode handler$$. - -$head msg$$ -The $icode handler$$ argument $icode msg$$ has prototype -$codei% - const char *%msg% -%$$ -and is a $code '\0'$$ terminated character vector. -It reports the meaning of the error from the C++ programmers point of view. - -$children% - example/error_handler.cpp% - cppad/local/cppad_assert.hpp -%$$ -$head Example$$ -The file -$cref error_handler.cpp$$ -contains an example and test a test of using this routine. -It returns true if it succeeds and false otherwise. - -$end ---------------------------------------------------------------------------- -*/ - -# include - -# include -# include -# include -# include - -namespace CppAD { // BEGIN CppAD namespace - -class ErrorHandler { - template - friend void parallel_ad(void); -public: - typedef void (*Handler) - (bool, int, const char *, const char *, const char *); - - // construct a new handler - ErrorHandler(Handler handler) : previous( Current() ) - { if( set_get_in_parallel(0) ) - { bool known = true; - int line = __LINE__; - const char* file = __FILE__; - const char* exp = "! set_get_in_parallel(0)"; - const char* msg = - "Using ErrorHandler constructor in parallel mode."; - Call(known, line, file, exp, msg); - } - Current() = handler; - } - - // destructor for an error handler - ~ErrorHandler(void) - { if( set_get_in_parallel(0) ) - { bool known = true; - int line = __LINE__; - const char* file = __FILE__; - const char* exp = "! set_get_in_parallel(0)"; - const char* msg = - "Using ErrorHandler destructor in parallel mode."; - Call(known, line, file, exp, msg); - } - Current() = previous; - } - - // report an error - static void Call( - bool known, - int line , - const char *file , - const char *exp , - const char *msg ) - { Handler handler = Current(); - handler(known, line, file, exp, msg); - } - -private: - const Handler previous; - - // The default error handler - static void Default( - bool known, - int line , - const char *file , - const char *exp , - const char *msg ) - { using std::cerr; - using std::endl; - - cerr << CPPAD_PACKAGE_STRING; - if( known ) - cerr << " error from a known source:" << endl; - else cerr << " error from unknown source" << endl; - if( msg[0] != '\0' ) - cerr << msg << endl; - cerr << "Error detected by false result for" << endl; - cerr << " " << exp << endl; - cerr << "at line " << line << " in the file " << endl; - cerr << " " << file << endl; - - // terminate program execution - assert(false); - - // termination when NDEBUG is defined - std::exit(1); - } - - // current error handler - static Handler &Current(void) - { static bool first_call = true; - static Handler current = Default; - if( first_call ) - { if( set_get_in_parallel(0) ) - { bool known = false; - int line = __LINE__; - const char* file = __FILE__; - const char* exp = ""; - const char* msg = ""; - Call(known, line, file, exp, msg); - } - first_call = false; - } - return current; - } -}; - -} // END CppAD namespace - - - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/index_sort.hpp b/ct_core/include/ct/external/cppad/utility/index_sort.hpp deleted file mode 100644 index a988dd0a8..000000000 --- a/ct_core/include/ct/external/cppad/utility/index_sort.hpp +++ /dev/null @@ -1,179 +0,0 @@ -// $Id: index_sort.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_INDEX_SORT_HPP -# define CPPAD_INDEX_SORT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin index_sort$$ -$spell - cppad.hpp - ind - const -$$ - -$section Returns Indices that Sort a Vector$$ -$mindex index_sort$$ - - -$head Syntax$$ -$codei%# include -%$$ -$codei%index_sort(%keys%, %ind%)%$$ - -$head keys$$ -The argument $icode keys$$ has prototype -$codei% - const %VectorKey%& %keys% -%$$ -where $icode VectorKey$$ is -a $cref SimpleVector$$ class with elements that support the $code <$$ -operation. - -$head ind$$ -The argument $icode ind$$ has prototype -$codei% - %VectorSize%& %ind% -%$$ -where $icode VectorSize$$ is -a $cref SimpleVector$$ class with elements of type $code size_t$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$subhead Input$$ -The size of $icode ind$$ must be the same as the size of $icode keys$$ -and the value of its input elements does not matter. - -$subhead Return$$ -Upon return, $icode ind$$ is a permutation of the set of indices -that yields increasing order for $icode keys$$. -In other words, for all $icode%i% != %j%$$, -$codei% - %ind%[%i%] != %ind%[%j%] -%$$ -and for $icode%i% = 0 , %...% , %size%-2%$$, -$codei% - ( %keys%[ %ind%[%i%+1] ] < %keys%[ %ind%[%i%] ] ) == false -%$$ - - -$head Example$$ -$children% - example/index_sort.cpp -%$$ -The file $cref index_sort.cpp$$ contains an example -and test of this routine. -It return true if it succeeds and false otherwise. - -$end -*/ -# include -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file index_sort.hpp -File used to implement the CppAD index sort utility -*/ - -/*! -Helper class used by index_sort -*/ -template -class index_sort_element { -private: - /// key used to determine position of this element - Compare key_; - /// index vlaue corresponding to this key - size_t index_; -public: - /// operator requried by std::sort - bool operator<(const index_sort_element& other) const - { return key_ < other.key_; } - /// set the key for this element - void set_key(const Compare& value) - { key_ = value; } - /// set the index for this element - void set_index(const size_t& index) - { index_ = index; } - /// get the key for this element - Compare get_key(void) const - { return key_; } - /// get the index for this element - size_t get_index(void) const - { return index_; } -}; - -/*! -Compute the indices that sort a vector of keys - -\tparam VectorKey -Simple vector type that deterimene the sorting order by \c < operator -on its elements. - -\tparam VectorSize -Simple vector type with elements of \c size_t -that is used to return index values. - -\param keys [in] -values that determine the sorting order. - -\param ind [out] -must have the same size as \c keys. -The input value of its elements does not matter. -The output value of its elements satisfy -\code -( keys[ ind[i] ] < keys[ ind[i+1] ] ) == false -\endcode -*/ -template -void index_sort(const VectorKey& keys, VectorSize& ind) -{ typedef typename VectorKey::value_type Compare; - CheckSimpleVector(); - - typedef index_sort_element element; - - CPPAD_ASSERT_KNOWN( - size_t(keys.size()) == size_t(ind.size()), - "index_sort: vector sizes do not match" - ); - - size_t size_work = size_t(keys.size()); - size_t size_out; - element* work = - thread_alloc::create_array(size_work, size_out); - - // copy initial order into work - size_t i; - for(i = 0; i < size_work; i++) - { work[i].set_key( keys[i] ); - work[i].set_index( i ); - } - - // sort the work array - std::sort(work, work+size_work); - - // copy the indices to the output vector - for(i = 0; i < size_work; i++) - ind[i] = work[i].get_index(); - - // we are done with this work array - thread_alloc::delete_array(work); - - return; -} - -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/lu_factor.hpp b/ct_core/include/ct/external/cppad/utility/lu_factor.hpp deleted file mode 100644 index 343079878..000000000 --- a/ct_core/include/ct/external/cppad/utility/lu_factor.hpp +++ /dev/null @@ -1,394 +0,0 @@ -// $Id: lu_factor.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_LU_FACTOR_HPP -# define CPPAD_LU_FACTOR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin LuFactor$$ -$escape #$$ -$spell - cppad.hpp - Cpp - Geq - Lu - bool - const - ip - jp - namespace - std - typename -$$ - - -$section LU Factorization of A Square Matrix$$ -$mindex LuFactor linear equation solve$$ - -$pre -$$ - -$head Syntax$$ $codei%# include -%$$ -$icode%sign% = LuFactor(%ip%, %jp%, %LU%)%$$ - - -$head Description$$ -Computes an LU factorization of the matrix $icode A$$ -where $icode A$$ is a square matrix. - -$head Include$$ -The file $code cppad/lu_factor.hpp$$ is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of -the $code CppAD$$ routines. - -$head Matrix Storage$$ -All matrices are stored in row major order. -To be specific, if $latex Y$$ is a vector -that contains a $latex p$$ by $latex q$$ matrix, -the size of $latex Y$$ must be equal to $latex p * q $$ and for -$latex i = 0 , \ldots , p-1$$, -$latex j = 0 , \ldots , q-1$$, -$latex \[ - Y_{i,j} = Y[ i * q + j ] -\] $$ - -$head sign$$ -The return value $icode sign$$ has prototype -$codei% - int %sign% -%$$ -If $icode A$$ is invertible, $icode sign$$ is plus or minus one -and is the sign of the permutation corresponding to the row ordering -$icode ip$$ and column ordering $icode jp$$. -If $icode A$$ is not invertible, $icode sign$$ is zero. - -$head ip$$ -The argument $icode ip$$ has prototype -$codei% - %SizeVector% &%ip% -%$$ -(see description of $cref/SizeVector/LuFactor/SizeVector/$$ below). -The size of $icode ip$$ is referred to as $icode n$$ in the -specifications below. -The input value of the elements of $icode ip$$ does not matter. -The output value of the elements of $icode ip$$ determine -the order of the rows in the permuted matrix. - -$head jp$$ -The argument $icode jp$$ has prototype -$codei% - %SizeVector% &%jp% -%$$ -(see description of $cref/SizeVector/LuFactor/SizeVector/$$ below). -The size of $icode jp$$ must be equal to $icode n$$. -The input value of the elements of $icode jp$$ does not matter. -The output value of the elements of $icode jp$$ determine -the order of the columns in the permuted matrix. - -$head LU$$ -The argument $icode LU$$ has the prototype -$codei% - %FloatVector% &%LU% -%$$ -and the size of $icode LU$$ must equal $latex n * n$$ -(see description of $cref/FloatVector/LuFactor/FloatVector/$$ below). - -$subhead A$$ -We define $icode A$$ as the matrix corresponding to the input -value of $icode LU$$. - -$subhead P$$ -We define the permuted matrix $icode P$$ in terms of $icode A$$ by -$codei% - %P%(%i%, %j%) = %A%[ %ip%[%i%] * %n% + %jp%[%j%] ] -%$$ - -$subhead L$$ -We define the lower triangular matrix $icode L$$ in terms of the -output value of $icode LU$$. -The matrix $icode L$$ is zero above the diagonal -and the rest of the elements are defined by -$codei% - %L%(%i%, %j%) = %LU%[ %ip%[%i%] * %n% + %jp%[%j%] ] -%$$ -for $latex i = 0 , \ldots , n-1$$ and $latex j = 0 , \ldots , i$$. - -$subhead U$$ -We define the upper triangular matrix $icode U$$ in terms of the -output value of $icode LU$$. -The matrix $icode U$$ is zero below the diagonal, -one on the diagonal, -and the rest of the elements are defined by -$codei% - %U%(%i%, %j%) = %LU%[ %ip%[%i%] * %n% + %jp%[%j%] ] -%$$ -for $latex i = 0 , \ldots , n-2$$ and $latex j = i+1 , \ldots , n-1$$. - -$subhead Factor$$ -If the return value $icode sign$$ is non-zero, -$codei% - %L% * %U% = %P% -%$$ -If the return value of $icode sign$$ is zero, -the contents of $icode L$$ and $icode U$$ are not defined. - -$subhead Determinant$$ -If the return value $icode sign$$ is zero, -the determinant of $icode A$$ is zero. -If $icode sign$$ is non-zero, -using the output value of $icode LU$$ -the determinant of the matrix $icode A$$ is equal to -$codei% -%sign% * %LU%[%ip%[0], %jp%[0]] * %...% * %LU%[%ip%[%n%-1], %jp%[%n%-1]] -%$$ - -$head SizeVector$$ -The type $icode SizeVector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type size_t/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head FloatVector$$ -The type $icode FloatVector$$ must be a -$cref/simple vector class/SimpleVector/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Float$$ -This notation is used to denote the type corresponding -to the elements of a $icode FloatVector$$. -The type $icode Float$$ must satisfy the conditions -for a $cref NumericType$$ type. -The routine $cref CheckNumericType$$ will generate an error message -if this is not the case. -In addition, the following operations must be defined for any pair -of $icode Float$$ objects $icode x$$ and $icode y$$: - -$table -$bold Operation$$ $cnext $bold Description$$ $rnext -$codei%log(%x%)%$$ $cnext - returns the logarithm of $icode x$$ as a $icode Float$$ object -$tend - -$head AbsGeq$$ -Including the file $code lu_factor.hpp$$ defines the template function -$codei% - template - bool AbsGeq<%Float%>(const %Float% &%x%, const %Float% &%y%) -%$$ -in the $code CppAD$$ namespace. -This function returns true if the absolute value of -$icode x$$ is greater than or equal the absolute value of $icode y$$. -It is used by $code LuFactor$$ to choose the pivot elements. -This template function definition uses the operator -$code <=$$ to obtain the absolute value for $icode Float$$ objects. -If this operator is not defined for your use of $icode Float$$, -you will need to specialize this template so that it works for your -use of $code LuFactor$$. -$pre - -$$ -Complex numbers do not have the operation $code <=$$ defined. -The specializations -$codei% -bool AbsGeq< std::complex > - (const std::complex &%x%, const std::complex &%y%) -bool AbsGeq< std::complex > - (const std::complex &%x%, const std::complex &%y%) -%$$ -are define by including $code lu_factor.hpp$$ -These return true if the sum of the square of the real and imaginary parts -of $icode x$$ is greater than or equal the -sum of the square of the real and imaginary parts of $icode y$$. - -$children% - example/lu_factor.cpp% - omh/lu_factor_hpp.omh -%$$ -$head Example$$ -The file -$cref lu_factor.cpp$$ -contains an example and test of using $code LuFactor$$ by itself. -It returns true if it succeeds and false otherwise. -$pre - -$$ -The file $cref lu_solve.hpp$$ provides a useful example usage of -$code LuFactor$$ with $code LuInvert$$. - -$head Source$$ -The file $cref lu_factor.hpp$$ contains the -current source code that implements these specifications. - -$end --------------------------------------------------------------------------- -*/ -// BEGIN C++ - -# include -# include - -# include -# include -# include - -namespace CppAD { // BEGIN CppAD namespace - -// AbsGeq -template -inline bool AbsGeq(const Float &x, const Float &y) -{ Float xabs = x; - if( xabs <= Float(0) ) - xabs = - xabs; - Float yabs = y; - if( yabs <= Float(0) ) - yabs = - yabs; - return xabs >= yabs; -} -inline bool AbsGeq( - const std::complex &x, - const std::complex &y) -{ double xsq = x.real() * x.real() + x.imag() * x.imag(); - double ysq = y.real() * y.real() + y.imag() * y.imag(); - - return xsq >= ysq; -} -inline bool AbsGeq( - const std::complex &x, - const std::complex &y) -{ float xsq = x.real() * x.real() + x.imag() * x.imag(); - float ysq = y.real() * y.real() + y.imag() * y.imag(); - - return xsq >= ysq; -} - -// Lines that are different from code in cppad/local/lu_ratio.hpp end with // -template // -int LuFactor(SizeVector &ip, SizeVector &jp, FloatVector &LU) // -{ - // type of the elements of LU // - typedef typename FloatVector::value_type Float; // - - // check numeric type specifications - CheckNumericType(); - - // check simple vector class specifications - CheckSimpleVector(); - CheckSimpleVector(); - - size_t i, j; // some temporary indices - const Float zero( 0 ); // the value zero as a Float object - size_t imax; // row index of maximum element - size_t jmax; // column indx of maximum element - Float emax; // maximum absolute value - size_t p; // count pivots - int sign; // sign of the permutation - Float etmp; // temporary element - Float pivot; // pivot element - - // ------------------------------------------------------- - size_t n = ip.size(); - CPPAD_ASSERT_KNOWN( - size_t(jp.size()) == n, - "Error in LuFactor: jp must have size equal to n" - ); - CPPAD_ASSERT_KNOWN( - size_t(LU.size()) == n * n, - "Error in LuFactor: LU must have size equal to n * m" - ); - // ------------------------------------------------------- - - // initialize row and column order in matrix not yet pivoted - for(i = 0; i < n; i++) - { ip[i] = i; - jp[i] = i; - } - // initialize the sign of the permutation - sign = 1; - // --------------------------------------------------------- - - // Reduce the matrix P to L * U using n pivots - for(p = 0; p < n; p++) - { // determine row and column corresponding to element of - // maximum absolute value in remaining part of P - imax = jmax = n; - emax = zero; - for(i = p; i < n; i++) - { for(j = p; j < n; j++) - { CPPAD_ASSERT_UNKNOWN( - (ip[i] < n) & (jp[j] < n) - ); - etmp = LU[ ip[i] * n + jp[j] ]; - - // check if maximum absolute value so far - if( AbsGeq (etmp, emax) ) - { imax = i; - jmax = j; - emax = etmp; - } - } - } - CPPAD_ASSERT_KNOWN( - (imax < n) & (jmax < n) , - "LuFactor can't determine an element with " - "maximum absolute value.\n" - "Perhaps original matrix contains not a number or infinity.\n" - "Perhaps your specialization of AbsGeq is not correct." - ); - if( imax != p ) - { // switch rows so max absolute element is in row p - i = ip[p]; - ip[p] = ip[imax]; - ip[imax] = i; - sign = -sign; - } - if( jmax != p ) - { // switch columns so max absolute element is in column p - j = jp[p]; - jp[p] = jp[jmax]; - jp[jmax] = j; - sign = -sign; - } - // pivot using the max absolute element - pivot = LU[ ip[p] * n + jp[p] ]; - - // check for determinant equal to zero - if( pivot == zero ) - { // abort the mission - return 0; - } - - // Reduce U by the elementary transformations that maps - // LU( ip[p], jp[p] ) to one. Only need transform elements - // above the diagonal in U and LU( ip[p] , jp[p] ) is - // corresponding value below diagonal in L. - for(j = p+1; j < n; j++) - LU[ ip[p] * n + jp[j] ] /= pivot; - - // Reduce U by the elementary transformations that maps - // LU( ip[i], jp[p] ) to zero. Only need transform elements - // above the diagonal in U and LU( ip[i], jp[p] ) is - // corresponding value below diagonal in L. - for(i = p+1; i < n; i++ ) - { etmp = LU[ ip[i] * n + jp[p] ]; - for(j = p+1; j < n; j++) - { LU[ ip[i] * n + jp[j] ] -= - etmp * LU[ ip[p] * n + jp[j] ]; - } - } - } - return sign; -} -} // END CppAD namespace -// END C++ -# endif diff --git a/ct_core/include/ct/external/cppad/utility/lu_invert.hpp b/ct_core/include/ct/external/cppad/utility/lu_invert.hpp deleted file mode 100644 index c5ee66bb0..000000000 --- a/ct_core/include/ct/external/cppad/utility/lu_invert.hpp +++ /dev/null @@ -1,240 +0,0 @@ -// $Id: lu_invert.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_LU_INVERT_HPP -# define CPPAD_LU_INVERT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin LuInvert$$ -$escape #$$ -$spell - cppad.hpp - Lu - Cpp - jp - ip - const - namespace - typename - etmp -$$ - - -$section Invert an LU Factored Equation$$ -$mindex LuInvert linear$$ - -$pre -$$ - -$head Syntax$$ $codei%# include -%$$ -$codei%LuInvert(%ip%, %jp%, %LU%, %X%)%$$ - - -$head Description$$ -Solves the matrix equation $icode%A% * %X% = %B%$$ -using an LU factorization computed by $cref LuFactor$$. - -$head Include$$ -The file $code cppad/lu_invert.hpp$$ is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of -the $code CppAD$$ routines. - -$head Matrix Storage$$ -All matrices are stored in row major order. -To be specific, if $latex Y$$ is a vector -that contains a $latex p$$ by $latex q$$ matrix, -the size of $latex Y$$ must be equal to $latex p * q $$ and for -$latex i = 0 , \ldots , p-1$$, -$latex j = 0 , \ldots , q-1$$, -$latex \[ - Y_{i,j} = Y[ i * q + j ] -\] $$ - -$head ip$$ -The argument $icode ip$$ has prototype -$codei% - const %SizeVector% &%ip% -%$$ -(see description for $icode SizeVector$$ in -$cref/LuFactor/LuFactor/SizeVector/$$ specifications). -The size of $icode ip$$ is referred to as $icode n$$ in the -specifications below. -The elements of $icode ip$$ determine -the order of the rows in the permuted matrix. - -$head jp$$ -The argument $icode jp$$ has prototype -$codei% - const %SizeVector% &%jp% -%$$ -(see description for $icode SizeVector$$ in -$cref/LuFactor/LuFactor/SizeVector/$$ specifications). -The size of $icode jp$$ must be equal to $icode n$$. -The elements of $icode jp$$ determine -the order of the columns in the permuted matrix. - -$head LU$$ -The argument $icode LU$$ has the prototype -$codei% - const %FloatVector% &%LU% -%$$ -and the size of $icode LU$$ must equal $latex n * n$$ -(see description for $icode FloatVector$$ in -$cref/LuFactor/LuFactor/FloatVector/$$ specifications). - -$subhead L$$ -We define the lower triangular matrix $icode L$$ in terms of $icode LU$$. -The matrix $icode L$$ is zero above the diagonal -and the rest of the elements are defined by -$codei% - %L%(%i%, %j%) = %LU%[ %ip%[%i%] * %n% + %jp%[%j%] ] -%$$ -for $latex i = 0 , \ldots , n-1$$ and $latex j = 0 , \ldots , i$$. - -$subhead U$$ -We define the upper triangular matrix $icode U$$ in terms of $icode LU$$. -The matrix $icode U$$ is zero below the diagonal, -one on the diagonal, -and the rest of the elements are defined by -$codei% - %U%(%i%, %j%) = %LU%[ %ip%[%i%] * %n% + %jp%[%j%] ] -%$$ -for $latex i = 0 , \ldots , n-2$$ and $latex j = i+1 , \ldots , n-1$$. - -$subhead P$$ -We define the permuted matrix $icode P$$ in terms of -the matrix $icode L$$ and the matrix $icode U$$ -by $icode%P% = %L% * %U%$$. - -$subhead A$$ -The matrix $icode A$$, -which defines the linear equations that we are solving, is given by -$codei% - %P%(%i%, %j%) = %A%[ %ip%[%i%] * %n% + %jp%[%j%] ] -%$$ -(Hence -$icode LU$$ contains a permuted factorization of the matrix $icode A$$.) - - -$head X$$ -The argument $icode X$$ has prototype -$codei% - %FloatVector% &%X% -%$$ -(see description for $icode FloatVector$$ in -$cref/LuFactor/LuFactor/FloatVector/$$ specifications). -The matrix $icode X$$ -must have the same number of rows as the matrix $icode A$$. -The input value of $icode X$$ is the matrix $icode B$$ and the -output value solves the matrix equation $icode%A% * %X% = %B%$$. - - -$children% - example/lu_invert.cpp% - omh/lu_invert_hpp.omh -%$$ -$head Example$$ -The file $cref lu_solve.hpp$$ is a good example usage of -$code LuFactor$$ with $code LuInvert$$. -The file -$cref lu_invert.cpp$$ -contains an example and test of using $code LuInvert$$ by itself. -It returns true if it succeeds and false otherwise. - -$head Source$$ -The file $cref lu_invert.hpp$$ contains the -current source code that implements these specifications. - -$end --------------------------------------------------------------------------- -*/ -// BEGIN C++ -# include -# include -# include - -namespace CppAD { // BEGIN CppAD namespace - -// LuInvert -template -void LuInvert( - const SizeVector &ip, - const SizeVector &jp, - const FloatVector &LU, - FloatVector &B ) -{ size_t k; // column index in X - size_t p; // index along diagonal in LU - size_t i; // row index in LU and X - - typedef typename FloatVector::value_type Float; - - // check numeric type specifications - CheckNumericType(); - - // check simple vector class specifications - CheckSimpleVector(); - CheckSimpleVector(); - - Float etmp; - - size_t n = ip.size(); - CPPAD_ASSERT_KNOWN( - size_t(jp.size()) == n, - "Error in LuInvert: jp must have size equal to n * n" - ); - CPPAD_ASSERT_KNOWN( - size_t(LU.size()) == n * n, - "Error in LuInvert: Lu must have size equal to n * m" - ); - size_t m = size_t(B.size()) / n; - CPPAD_ASSERT_KNOWN( - size_t(B.size()) == n * m, - "Error in LuSolve: B must have size equal to a multiple of n" - ); - - // temporary storage for reordered solution - FloatVector x(n); - - // loop over equations - for(k = 0; k < m; k++) - { // invert the equation c = L * b - for(p = 0; p < n; p++) - { // solve for c[p] - etmp = B[ ip[p] * m + k ] / LU[ ip[p] * n + jp[p] ]; - B[ ip[p] * m + k ] = etmp; - // subtract off effect on other variables - for(i = p+1; i < n; i++) - B[ ip[i] * m + k ] -= - etmp * LU[ ip[i] * n + jp[p] ]; - } - - // invert the equation x = U * c - p = n; - while( p > 0 ) - { --p; - etmp = B[ ip[p] * m + k ]; - x[ jp[p] ] = etmp; - for(i = 0; i < p; i++ ) - B[ ip[i] * m + k ] -= - etmp * LU[ ip[i] * n + jp[p] ]; - } - - // copy reordered solution into B - for(i = 0; i < n; i++) - B[i * m + k] = x[i]; - } - return; -} -} // END CppAD namespace -// END C++ -# endif diff --git a/ct_core/include/ct/external/cppad/utility/lu_solve.hpp b/ct_core/include/ct/external/cppad/utility/lu_solve.hpp deleted file mode 100644 index f22fd4861..000000000 --- a/ct_core/include/ct/external/cppad/utility/lu_solve.hpp +++ /dev/null @@ -1,346 +0,0 @@ -// $Id: lu_solve.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_LU_SOLVE_HPP -# define CPPAD_LU_SOLVE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin LuSolve$$ -$escape #$$ -$spell - cppad.hpp - det - exp - Leq - typename - bool - const - namespace - std - Geq - Lu - CppAD - signdet - logdet -$$ - - -$section Compute Determinant and Solve Linear Equations$$ -$mindex LuSolve Lu$$ - -$pre -$$ - -$head Syntax$$ $codei%# include -%$$ -$icode%signdet% = LuSolve(%n%, %m%, %A%, %B%, %X%, %logdet%)%$$ - - -$head Description$$ -Use an LU factorization of the matrix $icode A$$ to -compute its determinant -and solve for $icode X$$ in the linear of equation -$latex \[ - A * X = B -\] $$ -where $icode A$$ is an -$icode n$$ by $icode n$$ matrix, -$icode X$$ is an -$icode n$$ by $icode m$$ matrix, and -$icode B$$ is an $latex n x m$$ matrix. - -$head Include$$ -The file $code cppad/lu_solve.hpp$$ is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of -the $code CppAD$$ routines. - -$head Factor and Invert$$ -This routine is an easy to user interface to -$cref LuFactor$$ and $cref LuInvert$$ for computing determinants and -solutions of linear equations. -These separate routines should be used if -one right hand side $icode B$$ -depends on the solution corresponding to another -right hand side (with the same value of $icode A$$). -In this case only one call to $code LuFactor$$ is required -but there will be multiple calls to $code LuInvert$$. - - -$head Matrix Storage$$ -All matrices are stored in row major order. -To be specific, if $latex Y$$ is a vector -that contains a $latex p$$ by $latex q$$ matrix, -the size of $latex Y$$ must be equal to $latex p * q $$ and for -$latex i = 0 , \ldots , p-1$$, -$latex j = 0 , \ldots , q-1$$, -$latex \[ - Y_{i,j} = Y[ i * q + j ] -\] $$ - -$head signdet$$ -The return value $icode signdet$$ is a $code int$$ value -that specifies the sign factor for the determinant of $icode A$$. -This determinant of $icode A$$ is zero if and only if $icode signdet$$ -is zero. - -$head n$$ -The argument $icode n$$ has type $code size_t$$ -and specifies the number of rows in the matrices -$icode A$$, -$icode X$$, -and $icode B$$. -The number of columns in $icode A$$ is also equal to $icode n$$. - -$head m$$ -The argument $icode m$$ has type $code size_t$$ -and specifies the number of columns in the matrices -$icode X$$ -and $icode B$$. -If $icode m$$ is zero, -only the determinant of $icode A$$ is computed and -the matrices $icode X$$ and $icode B$$ are not used. - -$head A$$ -The argument $icode A$$ has the prototype -$codei% - const %FloatVector% &%A% -%$$ -and the size of $icode A$$ must equal $latex n * n$$ -(see description of $cref/FloatVector/LuSolve/FloatVector/$$ below). -This is the $latex n$$ by $icode n$$ matrix that -we are computing the determinant of -and that defines the linear equation. - -$head B$$ -The argument $icode B$$ has the prototype -$codei% - const %FloatVector% &%B% -%$$ -and the size of $icode B$$ must equal $latex n * m$$ -(see description of $cref/FloatVector/LuSolve/FloatVector/$$ below). -This is the $latex n$$ by $icode m$$ matrix that -defines the right hand side of the linear equations. -If $icode m$$ is zero, $icode B$$ is not used. - -$head X$$ -The argument $icode X$$ has the prototype -$codei% - %FloatVector% &%X% -%$$ -and the size of $icode X$$ must equal $latex n * m$$ -(see description of $cref/FloatVector/LuSolve/FloatVector/$$ below). -The input value of $icode X$$ does not matter. -On output, the elements of $icode X$$ contain the solution -of the equation we wish to solve -(unless $icode signdet$$ is equal to zero). -If $icode m$$ is zero, $icode X$$ is not used. - -$head logdet$$ -The argument $icode logdet$$ has prototype -$codei% - %Float% &%logdet% -%$$ -On input, the value of $icode logdet$$ does not matter. -On output, it has been set to the -log of the determinant of $icode A$$ -(but not quite). -To be more specific, -the determinant of $icode A$$ is given by the formula -$codei% - %det% = %signdet% * exp( %logdet% ) -%$$ -This enables $code LuSolve$$ to use logs of absolute values -in the case where $icode Float$$ corresponds to a real number. - -$head Float$$ -The type $icode Float$$ must satisfy the conditions -for a $cref NumericType$$ type. -The routine $cref CheckNumericType$$ will generate an error message -if this is not the case. -In addition, the following operations must be defined for any pair -of $icode Float$$ objects $icode x$$ and $icode y$$: - -$table -$bold Operation$$ $cnext $bold Description$$ $rnext -$codei%log(%x%)%$$ $cnext - returns the logarithm of $icode x$$ as a $icode Float$$ object -$tend - -$head FloatVector$$ -The type $icode FloatVector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type Float/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head LeqZero$$ -Including the file $code lu_solve.hpp$$ defines the template function -$codei% - template - bool LeqZero<%Float%>(const %Float% &%x%) -%$$ -in the $code CppAD$$ namespace. -This function returns true if $icode x$$ is less than or equal to zero -and false otherwise. -It is used by $code LuSolve$$ to avoid taking the log of -zero (or a negative number if $icode Float$$ corresponds to real numbers). -This template function definition assumes that the operator -$code <=$$ is defined for $icode Float$$ objects. -If this operator is not defined for your use of $icode Float$$, -you will need to specialize this template so that it works for your -use of $code LuSolve$$. -$pre - -$$ -Complex numbers do not have the operation or $code <=$$ defined. -In addition, in the complex case, -one can take the log of a negative number. -The specializations -$codei% - bool LeqZero< std::complex > (const std::complex &%x%) - bool LeqZero< std::complex >(const std::complex &%x%) -%$$ -are defined by including $code lu_solve.hpp$$. -These return true if $icode x$$ is zero and false otherwise. - -$head AbsGeq$$ -Including the file $code lu_solve.hpp$$ defines the template function -$codei% - template - bool AbsGeq<%Float%>(const %Float% &%x%, const %Float% &%y%) -%$$ -If the type $icode Float$$ does not support the $code <=$$ operation -and it is not $code std::complex$$ or $code std::complex$$, -see the documentation for $code AbsGeq$$ in $cref/LuFactor/LuFactor/AbsGeq/$$. - -$children% - example/lu_solve.cpp% - omh/lu_solve_hpp.omh -%$$ -$head Example$$ -The file -$cref lu_solve.cpp$$ -contains an example and test of using this routine. -It returns true if it succeeds and false otherwise. - -$head Source$$ -The file $cref lu_solve.hpp$$ contains the -current source code that implements these specifications. - -$end --------------------------------------------------------------------------- -*/ -// BEGIN C++ -# include -# include - -// link exp for float and double cases -# include - -# include -# include -# include -# include -# include - -namespace CppAD { // BEGIN CppAD namespace - -// LeqZero -template -inline bool LeqZero(const Float &x) -{ return x <= Float(0); } -inline bool LeqZero( const std::complex &x ) -{ return x == std::complex(0); } -inline bool LeqZero( const std::complex &x ) -{ return x == std::complex(0); } - -// LuSolve -template -int LuSolve( - size_t n , - size_t m , - const FloatVector &A , - const FloatVector &B , - FloatVector &X , - Float &logdet ) -{ - // check numeric type specifications - CheckNumericType(); - - // check simple vector class specifications - CheckSimpleVector(); - - size_t p; // index of pivot element (diagonal of L) - int signdet; // sign of the determinant - Float pivot; // pivot element - - // the value zero - const Float zero(0); - - // pivot row and column order in the matrix - std::vector ip(n); - std::vector jp(n); - - // ------------------------------------------------------- - CPPAD_ASSERT_KNOWN( - size_t(A.size()) == n * n, - "Error in LuSolve: A must have size equal to n * n" - ); - CPPAD_ASSERT_KNOWN( - size_t(B.size()) == n * m, - "Error in LuSolve: B must have size equal to n * m" - ); - CPPAD_ASSERT_KNOWN( - size_t(X.size()) == n * m, - "Error in LuSolve: X must have size equal to n * m" - ); - // ------------------------------------------------------- - - // copy A so that it does not change - FloatVector Lu(A); - - // copy B so that it does not change - X = B; - - // Lu factor the matrix A - signdet = LuFactor(ip, jp, Lu); - - // compute the log of the determinant - logdet = Float(0); - for(p = 0; p < n; p++) - { // pivot using the max absolute element - pivot = Lu[ ip[p] * n + jp[p] ]; - - // check for determinant equal to zero - if( pivot == zero ) - { // abort the mission - logdet = Float(0); - return 0; - } - - // update the determinant - if( LeqZero ( pivot ) ) - { logdet += log( - pivot ); - signdet = - signdet; - } - else logdet += log( pivot ); - - } - - // solve the linear equations - LuInvert(ip, jp, Lu, X); - - // return the sign factor for the determinant - return signdet; -} -} // END CppAD namespace -// END C++ -# endif diff --git a/ct_core/include/ct/external/cppad/utility/memory_leak.hpp b/ct_core/include/ct/external/cppad/utility/memory_leak.hpp deleted file mode 100644 index 154905b45..000000000 --- a/ct_core/include/ct/external/cppad/utility/memory_leak.hpp +++ /dev/null @@ -1,215 +0,0 @@ -// $Id: memory_leak.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_MEMORY_LEAK_HPP -# define CPPAD_MEMORY_LEAK_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin memory_leak$$ -$spell - cppad - num - alloc - hpp - bool - inuse -$$ - -$section Memory Leak Detection$$ -$mindex memory_leak check static$$ - -$head Deprecated 2012-04-06$$ -This routine has been deprecated. -You should instead use the routine $cref ta_free_all$$. - -$head Syntax$$ -$codei%# include -%$$ -$icode%flag% = %memory_leak() -%$$ -$icode%flag% = %memory_leak(%add_static%)%$$ - -$head Purpose$$ -This routine checks that the are no memory leaks -caused by improper use of $cref thread_alloc$$ memory allocator. -The deprecated memory allocator $cref TrackNewDel$$ is also checked. -Memory errors in the deprecated $cref omp_alloc$$ allocator are -reported as being in $code thread_alloc$$. - -$head thread$$ -It is assumed that $cref/in_parallel()/ta_in_parallel/$$ is false -and $cref/thread_num/ta_thread_num/$$ is zero when -$code memory_leak$$ is called. - -$head add_static$$ -This argument has prototype -$codei% - size_t %add_static% -%$$ -and its default value is zero. -Static variables hold onto memory forever. -If the argument $icode add_static$$ is present (and non-zero), -$code memory_leak$$ adds this amount of memory to the -$cref/inuse/ta_inuse/$$ sum that corresponds to -static variables in the program. -A call with $icode add_static$$ should be make after -a routine that has static variables which -use $cref/get_memory/ta_get_memory/$$ to allocate memory. -The value of $icode add_static$$ should be the difference of -$codei% - thread_alloc::inuse(0) -%$$ -before and after the call. -Since multiple statics may be allocated in different places in the program, -it is expected that there will be multiple calls -that use this option. - -$head flag$$ -The return value $icode flag$$ has prototype -$codei% - bool %flag% -%$$ -If $icode add_static$$ is non-zero, -the return value for $code memory_leak$$ is false. -Otherwise, the return value for $code memory_leak$$ should be false -(indicating that the only allocated memory corresponds to static variables). - -$head inuse$$ -It is assumed that, when $code memory_leak$$ is called, -there should not be any memory -$cref/inuse/ta_inuse/$$ or $cref omp_inuse$$ for any thread -(except for inuse memory corresponding to static variables). -If there is, a message is printed and $code memory_leak$$ returns false. - -$head available$$ -It is assumed that, when $code memory_leak$$ is called, -there should not be any memory -$cref/available/ta_available/$$ or $cref omp_available$$ for any thread; -i.e., it all has been returned to the system. -If there is memory still available for any thread, -$code memory_leak$$ returns false. - -$head TRACK_COUNT$$ -It is assumed that, when $code memory_leak$$ is called, -$cref/TrackCount/TrackNewDel/TrackCount/$$ will return a zero value. -If it returns a non-zero value, -$code memory_leak$$ returns false. - -$head Error Message$$ -If this is the first call to $code memory_leak$$, no message is printed. -Otherwise, if it returns true, an error message is printed -to standard output describing the memory leak that was detected. - -$end -*/ -# include -# include -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file memory_leak.hpp -File that implements a memory check at end of a CppAD program -*/ - -/*! -Function that checks -allocator \c thread_alloc for misuse that results in memory leaks. -Deprecated routines in track_new_del.hpp and omp_alloc.hpp are also checked. - -\param add_static [in] -The amount specified by \c add_static is added to the amount -of memory that is expected to be used by thread zero for static variables. - -\return -If \c add_static is non-zero, the return value is \c false. -Otherwise, if one of the following errors is detected, -the return value is \c true: - -\li -Thread zero does not have the expected amount of inuse memory -(for static variables). -\li -A thread, other than thread zero, has any inuse memory. -\li -Any thread has available memory. - -\par -If an error is detected, diagnostic information is printed to standard -output. -*/ -inline bool memory_leak(size_t add_static = 0) -{ // CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL not necessary given asserts below - static size_t thread_zero_static_inuse = 0; - using std::cout; - using std::endl; - using CppAD::thread_alloc; - using CppAD::omp_alloc; - // -------------------------------------------------------------------- - CPPAD_ASSERT_KNOWN( - ! thread_alloc::in_parallel(), - "memory_leak: in_parallel() is true." - ); - CPPAD_ASSERT_KNOWN( - thread_alloc::thread_num() == 0, - "memory_leak: thread_num() is not zero." - ); - if( add_static != 0 ) - { thread_zero_static_inuse += add_static; - return false; - } - bool leak = false; - size_t thread = 0; - - // check that memory in use for thread zero corresponds to statics - size_t num_bytes = thread_alloc::inuse(thread); - if( num_bytes != thread_zero_static_inuse ) - { leak = true; - cout << "thread zero: static inuse = " << thread_zero_static_inuse; - cout << "current inuse(thread) = " << num_bytes << endl; - } - // check that no memory is currently available for this thread - num_bytes = thread_alloc::available(thread); - if( num_bytes != 0 ) - { leak = true; - cout << "thread zero: available = "; - cout << num_bytes << endl; - } - for(thread = 1; thread < CPPAD_MAX_NUM_THREADS; thread++) - { - // check that no memory is currently in use for this thread - num_bytes = thread_alloc::inuse(thread); - if( num_bytes != 0 ) - { leak = true; - cout << "thread " << thread << ": inuse(thread) = "; - cout << num_bytes << endl; - } - // check that no memory is currently available for this thread - num_bytes = thread_alloc::available(thread); - if( num_bytes != 0 ) - { leak = true; - cout << "thread " << thread << ": available(thread) = "; - cout << num_bytes << endl; - } - } - // ---------------------------------------------------------------------- - // check track_new_del - if( CPPAD_TRACK_COUNT() != 0 ) - { leak = true; - CppAD::TrackElement::Print(); - } - return leak; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/include/ct/external/cppad/utility/nan.hpp b/ct_core/include/ct/external/cppad/utility/nan.hpp deleted file mode 100644 index b3a72de9e..000000000 --- a/ct_core/include/ct/external/cppad/utility/nan.hpp +++ /dev/null @@ -1,194 +0,0 @@ -// $Id: nan.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_NAN_HPP -# define CPPAD_NAN_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin nan$$ -$spell - hasnan - cppad - hpp - CppAD - isnan - bool - const -$$ - -$section Obtain Nan or Determine if a Value is Nan$$ - -$head Syntax$$ -$codei%# include -%$$ -$icode%b% = isnan(%s%) -%$$ -$icode%b% = hasnan(%v%)%$$ - -$head Purpose$$ -It obtain and check for the value not a number $code nan$$. -The IEEE standard specifies that a floating point value $icode a$$ -is $code nan$$ if and only if the following returns true -$codei% - %a% != %a% -%$$ - -$head Include$$ -The file $code cppad/nan.hpp$$ is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of -the $code CppAD$$ routines. - -$subhead Macros$$ -Some C++ compilers use preprocessor symbols called $code nan$$ -and $code isnan$$. -These preprocessor symbols will no longer be defined after -this file is included. - -$head isnan$$ -This routine determines if a scalar value is $code nan$$. - -$subhead s$$ -The argument $icode s$$ has prototype -$codei% - const %Scalar% %s% -%$$ - -$subhead b$$ -The return value $icode b$$ has prototype -$codei% - bool %b% -%$$ -It is true if the value $icode s$$ is $code nan$$. - -$head hasnan$$ -This routine determines if a -$cref SimpleVector$$ has an element that is $code nan$$. - -$subhead v$$ -The argument $icode v$$ has prototype -$codei% - const %Vector% &%v% -%$$ -(see $cref/Vector/nan/Vector/$$ for the definition of $icode Vector$$). - -$subhead b$$ -The return value $icode b$$ has prototype -$codei% - bool %b% -%$$ -It is true if the vector $icode v$$ has a $code nan$$. - - -$head nan(zero)$$ - -$subhead Deprecated 2015-10-04$$ -This routine has been deprecated, use CppAD numeric limits -$cref/quiet_NaN/numeric_limits/quiet_NaN/$$ in its place. - -$subhead Syntax$$ -$icode%s% = nan(%z%) -%$$ - -$subhead z$$ -The argument $icode z$$ has prototype -$codei% - const %Scalar% &%z% -%$$ -and its value is zero -(see $cref/Scalar/nan/Scalar/$$ for the definition of $icode Scalar$$). - -$subhead s$$ -The return value $icode s$$ has prototype -$codei% - %Scalar% %s% -%$$ -It is the value $code nan$$ for this floating point type. - -$head Scalar$$ -The type $icode Scalar$$ must support the following operations; -$table -$bold Operation$$ $cnext $bold Description$$ $rnext -$icode%a% / %b%$$ $cnext - division operator (returns a $icode Scalar$$ object) -$rnext -$icode%a% == %b%$$ $cnext - equality operator (returns a $code bool$$ object) -$rnext -$icode%a% != %b%$$ $cnext - not equality operator (returns a $code bool$$ object) -$tend -Note that the division operator will be used with $icode a$$ and $icode b$$ -equal to zero. For some types (e.g. $code int$$) this may generate -an exception. No attempt is made to catch any such exception. - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -elements of type $icode Scalar$$. - -$children% - example/nan.cpp -%$$ -$head Example$$ -The file $cref nan.cpp$$ -contains an example and test of this routine. -It returns true if it succeeds and false otherwise. - -$end -*/ - -# include -# include - -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -/* -# define nan There must be a define for every CppAD undef -*/ -# ifdef nan -# undef nan -# endif - -/* -# define isnan There must be a define for every CppAD undef -*/ -# ifdef isnan -# undef isnan -# endif - -namespace CppAD { // BEGIN CppAD namespace - -template -inline bool isnan(const Scalar &s) -{ return (s != s); -} - -template -bool hasnan(const Vector &v) -{ - bool found_nan; - size_t i; - i = v.size(); - found_nan = false; - // on MS Visual Studio 2012, CppAD required in front of isnan ? - while(i--) - found_nan |= CppAD::isnan(v[i]); - return found_nan; -} - -template -inline Scalar nan(const Scalar &zero) -{ return zero / zero; -} - -} // End CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/near_equal.hpp b/ct_core/include/ct/external/cppad/utility/near_equal.hpp deleted file mode 100644 index 38325e79b..000000000 --- a/ct_core/include/ct/external/cppad/utility/near_equal.hpp +++ /dev/null @@ -1,269 +0,0 @@ -// $Id: near_equal.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_NEAR_EQUAL_HPP -# define CPPAD_NEAR_EQUAL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin NearEqual$$ -$spell - cppad.hpp - sqrt - cout - endl - Microsoft - std - Cpp - namespace - const - bool -$$ - -$section Determine if Two Values Are Nearly Equal$$ -$mindex NearEqual near absolute difference relative$$ - - -$head Syntax$$ - -$codei%# include -%$$ -$icode%b% = NearEqual(%x%, %y%, %r%, %a%)%$$ - - -$head Purpose$$ -Returns true, -if $icode x$$ and $icode y$$ are nearly equal, -and false otherwise. - -$head x$$ -The argument $icode x$$ -has one of the following possible prototypes -$codei% - const %Type% &%x%, - const std::complex<%Type%> &%x%, -%$$ - -$head y$$ -The argument $icode y$$ -has one of the following possible prototypes -$codei% - const %Type% &%y%, - const std::complex<%Type%> &%y%, -%$$ - -$head r$$ -The relative error criteria $icode r$$ has prototype -$codei% - const %Type% &%r% -%$$ -It must be greater than or equal to zero. -The relative error condition is defined as: -$latex \[ - | x - y | \leq r ( |x| + |y| ) -\] $$ - -$head a$$ -The absolute error criteria $icode a$$ has prototype -$codei% - const %Type% &%a% -%$$ -It must be greater than or equal to zero. -The absolute error condition is defined as: -$latex \[ - | x - y | \leq a -\] $$ - -$head b$$ -The return value $icode b$$ has prototype -$codei% - bool %b% -%$$ -If either $icode x$$ or $icode y$$ is infinite or not a number, -the return value is false. -Otherwise, if either the relative or absolute error -condition (defined above) is satisfied, the return value is true. -Otherwise, the return value is false. - -$head Type$$ -The type $icode Type$$ must be a -$cref NumericType$$. -The routine $cref CheckNumericType$$ will generate -an error message if this is not the case. -In addition, the following operations must be defined objects -$icode a$$ and $icode b$$ of type $icode Type$$: -$table -$bold Operation$$ $cnext - $bold Description$$ $rnext -$icode%a% <= %b%$$ $cnext - less that or equal operator (returns a $code bool$$ object) -$tend - -$head Include Files$$ -The file $code cppad/near_equal.hpp$$ is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of -the $code CppAD$$ routines. - -$head Example$$ -$children% - example/near_equal.cpp -%$$ -The file $cref near_equal.cpp$$ contains an example -and test of $code NearEqual$$. -It return true if it succeeds and false otherwise. - -$head Exercise$$ -Create and run a program that contains the following code: -$codep - using std::complex; - using std::cout; - using std::endl; - - complex one(1., 0), i(0., 1); - complex x = one / i; - complex y = - i; - double r = 1e-12; - double a = 0; - bool ok = CppAD::NearEqual(x, y, r, a); - if( ok ) - cout << "Ok" << endl; - else cout << "Error" << endl; -$$ - -$end - -*/ - -# include -# include -# include -# include - -namespace CppAD { // Begin CppAD namespace - -// determine if both x and y are finite values -template -bool near_equal_isfinite(const Type &x , const Type &y) -{ Type infinity = Type( std::numeric_limits::infinity() ); - - // handle bug where some compilers return true for nan == nan - bool xNan = x != x; - bool yNan = y != y; - - // infinite cases - bool xInf = (x == infinity || x == - infinity); - bool yInf = (x == infinity || x == - infinity); - - return ! (xNan | yNan | xInf | yInf); -} - -template -bool NearEqual(const Type &x, const Type &y, const Type &r, const Type &a) -{ - CheckNumericType(); - Type zero(0); - - CPPAD_ASSERT_KNOWN( - zero <= r, - "Error in NearEqual: relative error is less than zero" - ); - CPPAD_ASSERT_KNOWN( - zero <= a, - "Error in NearEqual: absolute error is less than zero" - ); - - // check for special cases - if( ! CppAD::near_equal_isfinite(x, y) ) - return false; - - Type ax = x; - if( ax <= zero ) - ax = - ax; - - Type ay = y; - if( ay <= zero ) - ay = - ay; - - Type ad = x - y; - if( ad <= zero ) - ad = - ad; - - if( ad <= a ) - return true; - - if( ad <= r * (ax + ay) ) - return true; - - return false; -} - -template -bool NearEqual( - const std::complex &x , - const std::complex &y , - const Type &r , - const Type & a ) -{ - CheckNumericType(); - Type zero(0); - - CPPAD_ASSERT_KNOWN( - zero <= r, - "Error in NearEqual: relative error is less than zero" - ); - CPPAD_ASSERT_KNOWN( - zero <= a, - "Error in NearEqual: absolute error is less than zero" - ); - - // check for special cases - if( ! CppAD::near_equal_isfinite(x.real(), x.imag()) ) - return false; - if( ! CppAD::near_equal_isfinite(y.real(), y.imag()) ) - return false; - - std::complex d = x - y; - - Type ad = std::abs(d); - if( ad <= a ) - return true; - - Type ax = std::abs(x); - Type ay = std::abs(y); - if( ad <= r * (ax + ay) ) - return true; - - return false; -} - -template -bool NearEqual( - const std::complex &x , - const Type &y , - const Type &r , - const Type & a ) -{ - return NearEqual(x, std::complex(y, Type(0)), r, a); -} - -template -bool NearEqual( - const Type &x , - const std::complex &y , - const Type &r , - const Type & a ) -{ - return NearEqual(std::complex(x, Type(0)), y, r, a); -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/ode_err_control.hpp b/ct_core/include/ct/external/cppad/utility/ode_err_control.hpp deleted file mode 100644 index e873e2ea0..000000000 --- a/ct_core/include/ct/external/cppad/utility/ode_err_control.hpp +++ /dev/null @@ -1,596 +0,0 @@ -// $Id: ode_err_control.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_ODE_ERR_CONTROL_HPP -# define CPPAD_ODE_ERR_CONTROL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin OdeErrControl$$ -$spell - cppad.hpp - nstep - maxabs - exp - scur - CppAD - xf - tf - xi - smin - smax - eabs - erel - ef - ta - tb - xa - xb - const - eb -$$ - - - -$section An Error Controller for ODE Solvers$$ -$mindex OdeErrControl differential equation$$ - -$head Syntax$$ -$codei%# include -%$$ -$icode%xf% = OdeErrControl(%method%, %ti%, %tf%, %xi%, - %smin%, %smax%, %scur%, %eabs%, %erel%, %ef% , %maxabs%, %nstep% )%$$ - - -$head Description$$ -Let $latex \B{R}$$ denote the real numbers -and let $latex F : \B{R} \times \B{R}^n \rightarrow \B{R}^n$$ be a smooth function. -We define $latex X : [ti , tf] \rightarrow \B{R}^n$$ by -the following initial value problem: -$latex \[ -\begin{array}{rcl} - X(ti) & = & xi \\ - X'(t) & = & F[t , X(t)] -\end{array} -\] $$ -The routine $code OdeErrControl$$ can be used to adjust the step size -used an arbitrary integration methods in order to be as fast as possible -and still with in a requested error bound. - -$head Include$$ -The file $code cppad/ode_err_control.hpp$$ is included by -$code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of -the $code CppAD$$ routines. - -$head Notation$$ -The template parameter types $cref/Scalar/OdeErrControl/Scalar/$$ and -$cref/Vector/OdeErrControl/Vector/$$ are documented below. - -$head xf$$ -The return value $icode xf$$ has the prototype -$codei% - %Vector% %xf% -%$$ -(see description of $cref/Vector/OdeErrControl/Vector/$$ below). -and the size of $icode xf$$ is equal to $icode n$$. -If $icode xf$$ contains not a number $cref nan$$, -see the discussion of $cref/step/OdeErrControl/Method/Nan/$$. - -$head Method$$ -The class $icode Method$$ -and the object $icode method$$ satisfy the following syntax -$codei% - %Method% &%method% -%$$ -The object $icode method$$ must support $code step$$ and -$code order$$ member functions defined below: - -$subhead step$$ -The syntax -$codei% - %method%.step(%ta%, %tb%, %xa%, %xb%, %eb%) -%$$ -executes one step of the integration method. -$codei% - -%ta% -%$$ -The argument $icode ta$$ has prototype -$codei% - const %Scalar% &%ta% -%$$ -It specifies the initial time for this step in the -ODE integration. -(see description of $cref/Scalar/OdeErrControl/Scalar/$$ below). -$codei% - -%tb% -%$$ -The argument $icode tb$$ has prototype -$codei% - const %Scalar% &%tb% -%$$ -It specifies the final time for this step in the -ODE integration. -$codei% - -%xa% -%$$ -The argument $icode xa$$ has prototype -$codei% - const %Vector% &%xa% -%$$ -and size $icode n$$. -It specifies the value of $latex X(ta)$$. -(see description of $cref/Vector/OdeErrControl/Vector/$$ below). -$codei% - -%xb% -%$$ -The argument value $icode xb$$ has prototype -$codei% - %Vector% &%xb% -%$$ -and size $icode n$$. -The input value of its elements does not matter. -On output, -it contains the approximation for $latex X(tb)$$ that the method obtains. -$codei% - -%eb% -%$$ -The argument value $icode eb$$ has prototype -$codei% - %Vector% &%eb% -%$$ -and size $icode n$$. -The input value of its elements does not matter. -On output, -it contains an estimate for the error in the approximation $icode xb$$. -It is assumed (locally) that the error bound in this approximation -nearly equal to $latex K (tb - ta)^m$$ -where $icode K$$ is a fixed constant and $icode m$$ -is the corresponding argument to $code CodeControl$$. - -$subhead Nan$$ -If any element of the vector $icode eb$$ or $icode xb$$ are -not a number $code nan$$, -the current step is considered to large. -If this happens with the current step size equal to $icode smin$$, -$code OdeErrControl$$ returns with $icode xf$$ and $icode ef$$ as vectors -of $code nan$$. - -$subhead order$$ -If $icode m$$ is $code size_t$$, -the object $icode method$$ must also support the following syntax -$codei% - %m% = %method%.order() -%$$ -The return value $icode m$$ is the order of the error estimate; -i.e., there is a constant K such that if $latex ti \leq ta \leq tb \leq tf$$, -$latex \[ - | eb(tb) | \leq K | tb - ta |^m -\] $$ -where $icode ta$$, $icode tb$$, and $icode eb$$ are as in -$icode%method%.step(%ta%, %tb%, %xa%, %xb%, %eb%)%$$ - - -$head ti$$ -The argument $icode ti$$ has prototype -$codei% - const %Scalar% &%ti% -%$$ -It specifies the initial time for the integration of -the differential equation. - - -$head tf$$ -The argument $icode tf$$ has prototype -$codei% - const %Scalar% &%tf% -%$$ -It specifies the final time for the integration of -the differential equation. - -$head xi$$ -The argument $icode xi$$ has prototype -$codei% - const %Vector% &%xi% -%$$ -and size $icode n$$. -It specifies value of $latex X(ti)$$. - -$head smin$$ -The argument $icode smin$$ has prototype -$codei% - const %Scalar% &%smin% -%$$ -The step size during a call to $icode method$$ is defined as -the corresponding value of $latex tb - ta$$. -If $latex tf - ti \leq smin$$, -the integration will be done in one step of size $icode tf - ti$$. -Otherwise, -the minimum value of $icode tb - ta$$ will be $latex smin$$ -except for the last two calls to $icode method$$ where it may be -as small as $latex smin / 2$$. - -$head smax$$ -The argument $icode smax$$ has prototype -$codei% - const %Scalar% &%smax% -%$$ -It specifies the maximum step size to use during the integration; -i.e., the maximum value for $latex tb - ta$$ in a call to $icode method$$. -The value of $icode smax$$ must be greater than or equal $icode smin$$. - -$head scur$$ -The argument $icode scur$$ has prototype -$codei% - %Scalar% &%scur% -%$$ -The value of $icode scur$$ is the suggested next step size, -based on error criteria, to try in the next call to $icode method$$. -On input it corresponds to the first call to $icode method$$, -in this call to $code OdeErrControl$$ (where $latex ta = ti$$). -On output it corresponds to the next call to $icode method$$, -in a subsequent call to $code OdeErrControl$$ (where $icode ta = tf$$). - -$head eabs$$ -The argument $icode eabs$$ has prototype -$codei% - const %Vector% &%eabs% -%$$ -and size $icode n$$. -Each of the elements of $icode eabs$$ must be -greater than or equal zero. -It specifies a bound for the absolute -error in the return value $icode xf$$ as an approximation for $latex X(tf)$$. -(see the -$cref/error criteria discussion/OdeErrControl/Error Criteria Discussion/$$ -below). - -$head erel$$ -The argument $icode erel$$ has prototype -$codei% - const %Scalar% &%erel% -%$$ -and is greater than or equal zero. -It specifies a bound for the relative -error in the return value $icode xf$$ as an approximation for $latex X(tf)$$ -(see the -$cref/error criteria discussion/OdeErrControl/Error Criteria Discussion/$$ -below). - -$head ef$$ -The argument value $icode ef$$ has prototype -$codei% - %Vector% &%ef% -%$$ -and size $icode n$$. -The input value of its elements does not matter. -On output, -it contains an estimated bound for the -absolute error in the approximation $icode xf$$; i.e., -$latex \[ - ef_i > | X( tf )_i - xf_i | -\] $$ -If on output $icode ef$$ contains not a number $code nan$$, -see the discussion of $cref/step/OdeErrControl/Method/Nan/$$. - -$head maxabs$$ -The argument $icode maxabs$$ is optional in the call to $code OdeErrControl$$. -If it is present, it has the prototype -$codei% - %Vector% &%maxabs% -%$$ -and size $icode n$$. -The input value of its elements does not matter. -On output, -it contains an estimate for the -maximum absolute value of $latex X(t)$$; i.e., -$latex \[ - maxabs[i] \approx \max \left\{ - | X( t )_i | \; : \; t \in [ti, tf] - \right\} -\] $$ - -$head nstep$$ -The argument $icode nstep$$ is optional in the call to $code OdeErrControl$$. -If it is present, it has the prototype -$codei% - %size_t% &%nstep% -%$$ -Its input value does not matter and its output value -is the number of calls to $icode%method%.step%$$ -used by $code OdeErrControl$$. - -$head Error Criteria Discussion$$ -The relative error criteria $icode erel$$ and -absolute error criteria $icode eabs$$ are enforced during each step of the -integration of the ordinary differential equations. -In addition, they are inversely scaled by the step size so that -the total error bound is less than the sum of the error bounds. -To be specific, if $latex \tilde{X} (t)$$ is the approximate solution -at time $latex t$$, -$icode ta$$ is the initial step time, -and $icode tb$$ is the final step time, -$latex \[ -\left| \tilde{X} (tb)_j - X (tb)_j \right| -\leq -\frac{tf - ti}{tb - ta} -\left[ eabs[j] + erel \; | \tilde{X} (tb)_j | \right] -\] $$ -If $latex X(tb)_j$$ is near zero for some $latex tb \in [ti , tf]$$, -and one uses an absolute error criteria $latex eabs[j]$$ of zero, -the error criteria above will force $code OdeErrControl$$ -to use step sizes equal to -$cref/smin/OdeErrControl/smin/$$ -for steps ending near $latex tb$$. -In this case, the error relative to $icode maxabs$$ can be judged after -$code OdeErrControl$$ returns. -If $icode ef$$ is to large relative to $icode maxabs$$, -$code OdeErrControl$$ can be called again -with a smaller value of $icode smin$$. - -$head Scalar$$ -The type $icode Scalar$$ must satisfy the conditions -for a $cref NumericType$$ type. -The routine $cref CheckNumericType$$ will generate an error message -if this is not the case. -In addition, the following operations must be defined for -$icode Scalar$$ objects $icode a$$ and $icode b$$: - -$table -$bold Operation$$ $cnext $bold Description$$ $rnext -$icode%a% <= %b%$$ $cnext - returns true (false) if $icode a$$ is less than or equal - (greater than) $icode b$$. -$rnext -$icode%a% == %b%$$ $cnext - returns true (false) if $icode a$$ is equal to $icode b$$. -$rnext -$codei%log(%a%)%$$ $cnext - returns a $icode Scalar$$ equal to the logarithm of $icode a$$ -$rnext -$codei%exp(%a%)%$$ $cnext - returns a $icode Scalar$$ equal to the exponential of $icode a$$ -$tend - - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type Scalar/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Example$$ -$children% - example/ode_err_control.cpp% - example/ode_err_maxabs.cpp -%$$ -The files -$cref ode_err_control.cpp$$ -and -$cref ode_err_maxabs.cpp$$ -contain examples and tests of using this routine. -They return true if they succeed and false otherwise. - -$head Theory$$ -Let $latex e(s)$$ be the error as a function of the -step size $latex s$$ and suppose that there is a constant -$latex K$$ such that $latex e(s) = K s^m$$. -Let $latex a$$ be our error bound. -Given the value of $latex e(s)$$, a step of size $latex \lambda s$$ -would be ok provided that -$latex \[ -\begin{array}{rcl} - a & \geq & e( \lambda s ) (tf - ti) / ( \lambda s ) \\ - a & \geq & K \lambda^m s^m (tf - ti) / ( \lambda s ) \\ - a & \geq & \lambda^{m-1} s^{m-1} (tf - ti) e(s) / s^m \\ - a & \geq & \lambda^{m-1} (tf - ti) e(s) / s \\ - \lambda^{m-1} & \leq & \frac{a}{e(s)} \frac{s}{tf - ti} -\end{array} -\] $$ -Thus if the right hand side of the last inequality is greater -than or equal to one, the step of size $latex s$$ is ok. - -$head Source Code$$ -The source code for this routine is in the file -$code cppad/ode_err_control.hpp$$. - -$end --------------------------------------------------------------------------- -*/ - -// link exp and log for float and double -# include - -# include -# include -# include - -namespace CppAD { // Begin CppAD namespace - -template -Vector OdeErrControl( - Method &method, - const Scalar &ti , - const Scalar &tf , - const Vector &xi , - const Scalar &smin , - const Scalar &smax , - Scalar &scur , - const Vector &eabs , - const Scalar &erel , - Vector &ef , - Vector &maxabs, - size_t &nstep ) -{ - // check simple vector class specifications - CheckSimpleVector(); - - size_t n = size_t(xi.size()); - - CPPAD_ASSERT_KNOWN( - smin <= smax, - "Error in OdeErrControl: smin > smax" - ); - CPPAD_ASSERT_KNOWN( - size_t(eabs.size()) == n, - "Error in OdeErrControl: size of eabs is not equal to n" - ); - CPPAD_ASSERT_KNOWN( - size_t(maxabs.size()) == n, - "Error in OdeErrControl: size of maxabs is not equal to n" - ); - size_t m = method.order(); - CPPAD_ASSERT_KNOWN( - m > 1, - "Error in OdeErrControl: m is less than or equal one" - ); - - bool ok; - bool minimum_step; - size_t i; - Vector xa(n), xb(n), eb(n), nan_vec(n); - - // initialization - Scalar zero(0); - Scalar one(1); - Scalar two(2); - Scalar three(3); - Scalar m1(m-1); - Scalar ta = ti; - for(i = 0; i < n; i++) - { nan_vec[i] = nan(zero); - ef[i] = zero; - xa[i] = xi[i]; - if( zero <= xi[i] ) - maxabs[i] = xi[i]; - else maxabs[i] = - xi[i]; - - } - nstep = 0; - - Scalar tb, step, lambda, axbi, a, r, root; - while( ! (ta == tf) ) - { // start with value suggested by error criteria - step = scur; - - // check maximum - if( smax <= step ) - step = smax; - - // check minimum - minimum_step = step <= smin; - if( minimum_step ) - step = smin; - - // check if near the end - if( tf <= ta + step * three / two ) - tb = tf; - else tb = ta + step; - - // try using this step size - nstep++; - method.step(ta, tb, xa, xb, eb); - step = tb - ta; - - // check if this steps error estimate is ok - ok = ! (hasnan(xb) || hasnan(eb)); - if( (! ok) && minimum_step ) - { ef = nan_vec; - return nan_vec; - } - - // compute value of lambda for this step - lambda = Scalar(10) * scur / step; - for(i = 0; i < n; i++) - { if( zero <= xb[i] ) - axbi = xb[i]; - else axbi = - xb[i]; - a = eabs[i] + erel * axbi; - if( ! (eb[i] == zero) ) - { r = ( a / eb[i] ) * step / (tf - ti); - root = exp( log(r) / m1 ); - if( root <= lambda ) - lambda = root; - } - } - if( ok && ( one <= lambda || step <= smin * three / two) ) - { // this step is within error limits or - // close to the minimum size - ta = tb; - for(i = 0; i < n; i++) - { xa[i] = xb[i]; - ef[i] = ef[i] + eb[i]; - if( zero <= xb[i] ) - axbi = xb[i]; - else axbi = - xb[i]; - if( axbi > maxabs[i] ) - maxabs[i] = axbi; - } - } - if( ! ok ) - { // decrease step an see if method will work this time - scur = step / two; - } - else if( ! (ta == tf) ) - { // step suggested by the error criteria is not used - // on the last step because it may be very small. - scur = lambda * step / two; - } - } - return xa; -} - -template -Vector OdeErrControl( - Method &method, - const Scalar &ti , - const Scalar &tf , - const Vector &xi , - const Scalar &smin , - const Scalar &smax , - Scalar &scur , - const Vector &eabs , - const Scalar &erel , - Vector &ef ) -{ Vector maxabs(xi.size()); - size_t nstep; - return OdeErrControl( - method, ti, tf, xi, smin, smax, scur, eabs, erel, ef, maxabs, nstep - ); -} - -template -Vector OdeErrControl( - Method &method, - const Scalar &ti , - const Scalar &tf , - const Vector &xi , - const Scalar &smin , - const Scalar &smax , - Scalar &scur , - const Vector &eabs , - const Scalar &erel , - Vector &ef , - Vector &maxabs) -{ size_t nstep; - return OdeErrControl( - method, ti, tf, xi, smin, smax, scur, eabs, erel, ef, maxabs, nstep - ); -} - -} // End CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/ode_gear.hpp b/ct_core/include/ct/external/cppad/utility/ode_gear.hpp deleted file mode 100644 index 09b70f101..000000000 --- a/ct_core/include/ct/external/cppad/utility/ode_gear.hpp +++ /dev/null @@ -1,521 +0,0 @@ -// $Id: ode_gear.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_ODE_GEAR_HPP -# define CPPAD_ODE_GEAR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin OdeGear$$ -$spell - cppad.hpp - Jan - bool - const - CppAD - dep -$$ - - -$section An Arbitrary Order Gear Method$$ -$mindex OdeGear Ode stiff differential equation$$ - -$head Syntax$$ -$codei%# include -%$$ -$codei%OdeGear(%F%, %m%, %n%, %T%, %X%, %e%)%$$ - - -$head Purpose$$ -This routine applies -$cref/Gear's Method/OdeGear/Gear's Method/$$ -to solve an explicit set of ordinary differential equations. -We are given -$latex f : \B{R} \times \B{R}^n \rightarrow \B{R}^n$$ be a smooth function. -This routine solves the following initial value problem -$latex \[ -\begin{array}{rcl} - x( t_{m-1} ) & = & x^0 \\ - x^\prime (t) & = & f[t , x(t)] -\end{array} -\] $$ -for the value of $latex x( t_m )$$. -If your set of ordinary differential equations are not stiff -an explicit method may be better (perhaps $cref Runge45$$.) - -$head Include$$ -The file $code cppad/ode_gear.hpp$$ is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of -the $code CppAD$$ routines. - -$head Fun$$ -The class $icode Fun$$ -and the object $icode F$$ satisfy the prototype -$codei% - %Fun% &%F% -%$$ -This must support the following set of calls -$codei% - %F%.Ode(%t%, %x%, %f%) - %F%.Ode_dep(%t%, %x%, %f_x%) -%$$ - -$subhead t$$ -The argument $icode t$$ has prototype -$codei% - const %Scalar% &%t% -%$$ -(see description of $cref/Scalar/OdeGear/Scalar/$$ below). - -$subhead x$$ -The argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -and has size $icode n$$ -(see description of $cref/Vector/OdeGear/Vector/$$ below). - -$subhead f$$ -The argument $icode f$$ to $icode%F%.Ode%$$ has prototype -$codei% - %Vector% &%f% -%$$ -On input and output, $icode f$$ is a vector of size $icode n$$ -and the input values of the elements of $icode f$$ do not matter. -On output, -$icode f$$ is set equal to $latex f(t, x)$$ -(see $icode f(t, x)$$ in $cref/Purpose/OdeGear/Purpose/$$). - -$subhead f_x$$ -The argument $icode f_x$$ has prototype -$codei% - %Vector% &%f_x% -%$$ -On input and output, $icode f_x$$ is a vector of size $latex n * n$$ -and the input values of the elements of $icode f_x$$ do not matter. -On output, -$latex \[ - f\_x [i * n + j] = \partial_{x(j)} f_i ( t , x ) -\] $$ - -$subhead Warning$$ -The arguments $icode f$$, and $icode f_x$$ -must have a call by reference in their prototypes; i.e., -do not forget the $code &$$ in the prototype for -$icode f$$ and $icode f_x$$. - -$head m$$ -The argument $icode m$$ has prototype -$codei% - size_t %m% -%$$ -It specifies the order (highest power of $latex t$$) -used to represent the function $latex x(t)$$ in the multi-step method. -Upon return from $code OdeGear$$, -the $th i$$ component of the polynomial is defined by -$latex \[ - p_i ( t_j ) = X[ j * n + i ] -\] $$ -for $latex j = 0 , \ldots , m$$ (where $latex 0 \leq i < n$$). -The value of $latex m$$ must be greater than or equal one. - -$head n$$ -The argument $icode n$$ has prototype -$codei% - size_t %n% -%$$ -It specifies the range space dimension of the -vector valued function $latex x(t)$$. - -$head T$$ -The argument $icode T$$ has prototype -$codei% - const %Vector% &%T% -%$$ -and size greater than or equal to $latex m+1$$. -For $latex j = 0 , \ldots m$$, $latex T[j]$$ is the time -corresponding to time corresponding -to a previous point in the multi-step method. -The value $latex T[m]$$ is the time -of the next point in the multi-step method. -The array $latex T$$ must be monotone increasing; i.e., -$latex T[j] < T[j+1]$$. -Above and below we often use the shorthand $latex t_j$$ for $latex T[j]$$. - - -$head X$$ -The argument $icode X$$ has the prototype -$codei% - %Vector% &%X% -%$$ -and size greater than or equal to $latex (m+1) * n$$. -On input to $code OdeGear$$, -for $latex j = 0 , \ldots , m-1$$, and -$latex i = 0 , \ldots , n-1$$ -$latex \[ - X[ j * n + i ] = x_i ( t_j ) -\] $$ -Upon return from $code OdeGear$$, -for $latex i = 0 , \ldots , n-1$$ -$latex \[ - X[ m * n + i ] \approx x_i ( t_m ) -\] $$ - -$head e$$ -The vector $icode e$$ is an approximate error bound for the result; i.e., -$latex \[ - e[i] \geq | X[ m * n + i ] - x_i ( t_m ) | -\] $$ -The order of this approximation is one less than the order of -the solution; i.e., -$latex \[ - e = O ( h^m ) -\] $$ -where $latex h$$ is the maximum of $latex t_{j+1} - t_j$$. - -$head Scalar$$ -The type $icode Scalar$$ must satisfy the conditions -for a $cref NumericType$$ type. -The routine $cref CheckNumericType$$ will generate an error message -if this is not the case. -In addition, the following operations must be defined for -$icode Scalar$$ objects $icode a$$ and $icode b$$: - -$table -$bold Operation$$ $cnext $bold Description$$ $rnext -$icode%a% < %b%$$ $cnext - less than operator (returns a $code bool$$ object) -$tend - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type Scalar/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Example$$ -$children% - example/ode_gear.cpp -%$$ -The file -$cref ode_gear.cpp$$ -contains an example and test a test of using this routine. -It returns true if it succeeds and false otherwise. - -$head Source Code$$ -The source code for this routine is in the file -$code cppad/ode_gear.hpp$$. - -$head Theory$$ -For this discussion we use the shorthand $latex x_j$$ -for the value $latex x ( t_j ) \in \B{R}^n$$ which is not to be confused -with $latex x_i (t) \in \B{R}$$ in the notation above. -The interpolating polynomial $latex p(t)$$ is given by -$latex \[ -p(t) = -\sum_{j=0}^m -x_j -\frac{ - \prod_{i \neq j} ( t - t_i ) -}{ - \prod_{i \neq j} ( t_j - t_i ) -} -\] $$ -The derivative $latex p^\prime (t)$$ is given by -$latex \[ -p^\prime (t) = -\sum_{j=0}^m -x_j -\frac{ - \sum_{i \neq j} \prod_{k \neq i,j} ( t - t_k ) -}{ - \prod_{k \neq j} ( t_j - t_k ) -} -\] $$ -Evaluating the derivative at the point $latex t_\ell$$ we have -$latex \[ -\begin{array}{rcl} -p^\prime ( t_\ell ) & = & -x_\ell -\frac{ - \sum_{i \neq \ell} \prod_{k \neq i,\ell} ( t_\ell - t_k ) -}{ - \prod_{k \neq \ell} ( t_\ell - t_k ) -} -+ -\sum_{j \neq \ell} -x_j -\frac{ - \sum_{i \neq j} \prod_{k \neq i,j} ( t_\ell - t_k ) -}{ - \prod_{k \neq j} ( t_j - t_k ) -} -\\ -& = & -x_\ell -\sum_{i \neq \ell} -\frac{ 1 }{ t_\ell - t_i } -+ -\sum_{j \neq \ell} -x_j -\frac{ - \prod_{k \neq \ell,j} ( t_\ell - t_k ) -}{ - \prod_{k \neq j} ( t_j - t_k ) -} -\\ -& = & -x_\ell -\sum_{k \neq \ell} ( t_\ell - t_k )^{-1} -+ -\sum_{j \neq \ell} -x_j -( t_j - t_\ell )^{-1} -\prod_{k \neq \ell ,j} ( t_\ell - t_k ) / ( t_j - t_k ) -\end{array} -\] $$ -We define the vector $latex \alpha \in \B{R}^{m+1}$$ by -$latex \[ -\alpha_j = \left\{ \begin{array}{ll} -\sum_{k \neq m} ( t_m - t_k )^{-1} - & {\rm if} \; j = m -\\ -( t_j - t_m )^{-1} -\prod_{k \neq m,j} ( t_m - t_k ) / ( t_j - t_k ) - & {\rm otherwise} -\end{array} \right. -\] $$ -It follows that -$latex \[ - p^\prime ( t_m ) = \alpha_0 x_0 + \cdots + \alpha_m x_m -\] $$ -Gear's method determines $latex x_m$$ by solving the following -nonlinear equation -$latex \[ - f( t_m , x_m ) = \alpha_0 x_0 + \cdots + \alpha_m x_m -\] $$ -Newton's method for solving this equation determines iterates, -which we denote by $latex x_m^k$$, by solving the following affine -approximation of the equation above -$latex \[ -\begin{array}{rcl} -f( t_m , x_m^{k-1} ) + \partial_x f( t_m , x_m^{k-1} ) ( x_m^k - x_m^{k-1} ) -& = & -\alpha_0 x_0^k + \alpha_1 x_1 + \cdots + \alpha_m x_m -\\ -\left[ \alpha_m I - \partial_x f( t_m , x_m^{k-1} ) \right] x_m -& = & -\left[ -f( t_m , x_m^{k-1} ) - \partial_x f( t_m , x_m^{k-1} ) x_m^{k-1} -- \alpha_0 x_0 - \cdots - \alpha_{m-1} x_{m-1} -\right] -\end{array} -\] $$ -In order to initialize Newton's method; i.e. choose $latex x_m^0$$ -we define the vector $latex \beta \in \B{R}^{m+1}$$ by -$latex \[ -\beta_j = \left\{ \begin{array}{ll} -\sum_{k \neq m-1} ( t_{m-1} - t_k )^{-1} - & {\rm if} \; j = m-1 -\\ -( t_j - t_{m-1} )^{-1} -\prod_{k \neq m-1,j} ( t_{m-1} - t_k ) / ( t_j - t_k ) - & {\rm otherwise} -\end{array} \right. -\] $$ -It follows that -$latex \[ - p^\prime ( t_{m-1} ) = \beta_0 x_0 + \cdots + \beta_m x_m -\] $$ -We solve the following approximation of the equation above to determine -$latex x_m^0$$: -$latex \[ - f( t_{m-1} , x_{m-1} ) = - \beta_0 x_0 + \cdots + \beta_{m-1} x_{m-1} + \beta_m x_m^0 -\] $$ - - -$head Gear's Method$$ -C. W. Gear, -``Simultaneous Numerical Solution of Differential-Algebraic Equations,'' -IEEE Transactions on Circuit Theory, -vol. 18, no. 1, pp. 89-95, Jan. 1971. - - -$end --------------------------------------------------------------------------- -*/ - -# include -# include -# include -# include -# include -# include -# include - -namespace CppAD { // BEGIN CppAD namespace - -template -void OdeGear( - Fun &F , - size_t m , - size_t n , - const Vector &T , - Vector &X , - Vector &e ) -{ - // temporary indices - size_t i, j, k; - - typedef typename Vector::value_type Scalar; - - // check numeric type specifications - CheckNumericType(); - - // check simple vector class specifications - CheckSimpleVector(); - - CPPAD_ASSERT_KNOWN( - m >= 1, - "OdeGear: m is less than one" - ); - CPPAD_ASSERT_KNOWN( - n > 0, - "OdeGear: n is equal to zero" - ); - CPPAD_ASSERT_KNOWN( - size_t(T.size()) >= (m+1), - "OdeGear: size of T is not greater than or equal (m+1)" - ); - CPPAD_ASSERT_KNOWN( - size_t(X.size()) >= (m+1) * n, - "OdeGear: size of X is not greater than or equal (m+1) * n" - ); - for(j = 0; j < m; j++) CPPAD_ASSERT_KNOWN( - T[j] < T[j+1], - "OdeGear: the array T is not monotone increasing" - ); - - // some constants - Scalar zero(0); - Scalar one(1); - - // vectors required by method - Vector alpha(m + 1); - Vector beta(m + 1); - Vector f(n); - Vector f_x(n * n); - Vector x_m0(n); - Vector x_m(n); - Vector b(n); - Vector A(n * n); - - // compute alpha[m] - alpha[m] = zero; - for(k = 0; k < m; k++) - alpha[m] += one / (T[m] - T[k]); - - // compute beta[m-1] - beta[m-1] = one / (T[m-1] - T[m]); - for(k = 0; k < m-1; k++) - beta[m-1] += one / (T[m-1] - T[k]); - - - // compute other components of alpha - for(j = 0; j < m; j++) - { // compute alpha[j] - alpha[j] = one / (T[j] - T[m]); - for(k = 0; k < m; k++) - { if( k != j ) - { alpha[j] *= (T[m] - T[k]); - alpha[j] /= (T[j] - T[k]); - } - } - } - - // compute other components of beta - for(j = 0; j <= m; j++) - { if( j != m-1 ) - { // compute beta[j] - beta[j] = one / (T[j] - T[m-1]); - for(k = 0; k <= m; k++) - { if( k != j && k != m-1 ) - { beta[j] *= (T[m-1] - T[k]); - beta[j] /= (T[j] - T[k]); - } - } - } - } - - // evaluate f(T[m-1], x_{m-1} ) - for(i = 0; i < n; i++) - x_m[i] = X[(m-1) * n + i]; - F.Ode(T[m-1], x_m, f); - - // solve for x_m^0 - for(i = 0; i < n; i++) - { x_m[i] = f[i]; - for(j = 0; j < m; j++) - x_m[i] -= beta[j] * X[j * n + i]; - x_m[i] /= beta[m]; - } - x_m0 = x_m; - - // evaluate partial w.r.t x of f(T[m], x_m^0) - F.Ode_dep(T[m], x_m, f_x); - - // compute the matrix A = ( alpha[m] * I - f_x ) - for(i = 0; i < n; i++) - { for(j = 0; j < n; j++) - A[i * n + j] = - f_x[i * n + j]; - A[i * n + i] += alpha[m]; - } - - // LU factor (and overwrite) the matrix A - int sign; - CppAD::vector ip(n) , jp(n); - sign = LuFactor(ip, jp, A); - CPPAD_ASSERT_KNOWN( - sign != 0, - "OdeGear: step size is to large" - ); - - // Iterations of Newton's method - for(k = 0; k < 3; k++) - { - // only evaluate f( T[m] , x_m ) keep f_x during iteration - F.Ode(T[m], x_m, f); - - // b = f + f_x x_m - alpha[0] x_0 - ... - alpha[m-1] x_{m-1} - for(i = 0; i < n; i++) - { b[i] = f[i]; - for(j = 0; j < n; j++) - b[i] -= f_x[i * n + j] * x_m[j]; - for(j = 0; j < m; j++) - b[i] -= alpha[j] * X[ j * n + i ]; - } - LuInvert(ip, jp, A, b); - x_m = b; - } - - // return estimate for x( t[k] ) and the estimated error bound - for(i = 0; i < n; i++) - { X[m * n + i] = x_m[i]; - e[i] = x_m[i] - x_m0[i]; - if( e[i] < zero ) - e[i] = - e[i]; - } -} - -} // End CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/ode_gear_control.hpp b/ct_core/include/ct/external/cppad/utility/ode_gear_control.hpp deleted file mode 100644 index 01d636bbd..000000000 --- a/ct_core/include/ct/external/cppad/utility/ode_gear_control.hpp +++ /dev/null @@ -1,543 +0,0 @@ -// $Id: ode_gear_control.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_ODE_GEAR_CONTROL_HPP -# define CPPAD_ODE_GEAR_CONTROL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin OdeGearControl$$ -$spell - cppad.hpp - CppAD - xf - xi - smin - smax - eabs - ef - maxabs - nstep - tf - sini - erel - dep - const - tb - ta - exp -$$ - - - -$section An Error Controller for Gear's Ode Solvers$$ -$mindex OdeGearControl Gear differential equation$$ - -$head Syntax$$ -$codei%# include -%$$ -$icode%xf% = OdeGearControl(%F%, %M%, %ti%, %tf%, %xi%, - %smin%, %smax%, %sini%, %eabs%, %erel%, %ef% , %maxabs%, %nstep% )%$$ - - -$head Purpose$$ -Let $latex \B{R}$$ denote the real numbers -and let $latex f : \B{R} \times \B{R}^n \rightarrow \B{R}^n$$ be a smooth function. -We define $latex X : [ti , tf] \rightarrow \B{R}^n$$ by -the following initial value problem: -$latex \[ -\begin{array}{rcl} - X(ti) & = & xi \\ - X'(t) & = & f[t , X(t)] -\end{array} -\] $$ -The routine $cref OdeGear$$ is a stiff multi-step method that -can be used to approximate the solution to this equation. -The routine $code OdeGearControl$$ sets up this multi-step method -and controls the error during such an approximation. - -$head Include$$ -The file $code cppad/ode_gear_control.hpp$$ -is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of -the $code CppAD$$ routines. - -$head Notation$$ -The template parameter types $cref/Scalar/OdeGearControl/Scalar/$$ and -$cref/Vector/OdeGearControl/Vector/$$ are documented below. - -$head xf$$ -The return value $icode xf$$ has the prototype -$codei% - %Vector% %xf% -%$$ -and the size of $icode xf$$ is equal to $icode n$$ -(see description of $cref/Vector/OdeGear/Vector/$$ below). -It is the approximation for $latex X(tf)$$. - -$head Fun$$ -The class $icode Fun$$ -and the object $icode F$$ satisfy the prototype -$codei% - %Fun% &%F% -%$$ -This must support the following set of calls -$codei% - %F%.Ode(%t%, %x%, %f%) - %F%.Ode_dep(%t%, %x%, %f_x%) -%$$ - -$subhead t$$ -The argument $icode t$$ has prototype -$codei% - const %Scalar% &%t% -%$$ -(see description of $cref/Scalar/OdeGear/Scalar/$$ below). - -$subhead x$$ -The argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -and has size $icode N$$ -(see description of $cref/Vector/OdeGear/Vector/$$ below). - -$subhead f$$ -The argument $icode f$$ to $icode%F%.Ode%$$ has prototype -$codei% - %Vector% &%f% -%$$ -On input and output, $icode f$$ is a vector of size $icode N$$ -and the input values of the elements of $icode f$$ do not matter. -On output, -$icode f$$ is set equal to $latex f(t, x)$$ -(see $icode f(t, x)$$ in $cref/Purpose/OdeGear/Purpose/$$). - -$subhead f_x$$ -The argument $icode f_x$$ has prototype -$codei% - %Vector% &%f_x% -%$$ -On input and output, $icode f_x$$ is a vector of size $latex N * N$$ -and the input values of the elements of $icode f_x$$ do not matter. -On output, -$latex \[ - f\_x [i * n + j] = \partial_{x(j)} f_i ( t , x ) -\] $$ - -$subhead Warning$$ -The arguments $icode f$$, and $icode f_x$$ -must have a call by reference in their prototypes; i.e., -do not forget the $code &$$ in the prototype for -$icode f$$ and $icode f_x$$. - -$head M$$ -The argument $icode M$$ has prototype -$codei% - size_t %M% -%$$ -It specifies the order of the multi-step method; i.e., -the order of the approximating polynomial -(after the initialization process). -The argument $icode M$$ must greater than or equal one. - -$head ti$$ -The argument $icode ti$$ has prototype -$codei% - const %Scalar% &%ti% -%$$ -It specifies the initial time for the integration of -the differential equation. - -$head tf$$ -The argument $icode tf$$ has prototype -$codei% - const %Scalar% &%tf% -%$$ -It specifies the final time for the integration of -the differential equation. - -$head xi$$ -The argument $icode xi$$ has prototype -$codei% - const %Vector% &%xi% -%$$ -and size $icode n$$. -It specifies value of $latex X(ti)$$. - -$head smin$$ -The argument $icode smin$$ has prototype -$codei% - const %Scalar% &%smin% -%$$ -The minimum value of $latex T[M] - T[M-1]$$ in a call to $code OdeGear$$ -will be $latex smin$$ except for the last two calls where it may be -as small as $latex smin / 2$$. -The value of $icode smin$$ must be less than or equal $icode smax$$. - -$head smax$$ -The argument $icode smax$$ has prototype -$codei% - const %Scalar% &%smax% -%$$ -It specifies the maximum step size to use during the integration; -i.e., the maximum value for $latex T[M] - T[M-1]$$ -in a call to $code OdeGear$$. - -$head sini$$ -The argument $icode sini$$ has prototype -$codei% - %Scalar% &%sini% -%$$ -The value of $icode sini$$ is the minimum -step size to use during initialization of the multi-step method; i.e., -for calls to $code OdeGear$$ where $latex m < M$$. -The value of $icode sini$$ must be less than or equal $icode smax$$ -(and can also be less than $icode smin$$). - -$head eabs$$ -The argument $icode eabs$$ has prototype -$codei% - const %Vector% &%eabs% -%$$ -and size $icode n$$. -Each of the elements of $icode eabs$$ must be -greater than or equal zero. -It specifies a bound for the absolute -error in the return value $icode xf$$ as an approximation for $latex X(tf)$$. -(see the -$cref/error criteria discussion/OdeGearControl/Error Criteria Discussion/$$ -below). - -$head erel$$ -The argument $icode erel$$ has prototype -$codei% - const %Scalar% &%erel% -%$$ -and is greater than or equal zero. -It specifies a bound for the relative -error in the return value $icode xf$$ as an approximation for $latex X(tf)$$ -(see the -$cref/error criteria discussion/OdeGearControl/Error Criteria Discussion/$$ -below). - -$head ef$$ -The argument value $icode ef$$ has prototype -$codei% - %Vector% &%ef% -%$$ -and size $icode n$$. -The input value of its elements does not matter. -On output, -it contains an estimated bound for the -absolute error in the approximation $icode xf$$; i.e., -$latex \[ - ef_i > | X( tf )_i - xf_i | -\] $$ - -$head maxabs$$ -The argument $icode maxabs$$ is optional in the call to $code OdeGearControl$$. -If it is present, it has the prototype -$codei% - %Vector% &%maxabs% -%$$ -and size $icode n$$. -The input value of its elements does not matter. -On output, -it contains an estimate for the -maximum absolute value of $latex X(t)$$; i.e., -$latex \[ - maxabs[i] \approx \max \left\{ - | X( t )_i | \; : \; t \in [ti, tf] - \right\} -\] $$ - -$head nstep$$ -The argument $icode nstep$$ has the prototype -$codei% - %size_t% &%nstep% -%$$ -Its input value does not matter and its output value -is the number of calls to $cref OdeGear$$ -used by $code OdeGearControl$$. - -$head Error Criteria Discussion$$ -The relative error criteria $icode erel$$ and -absolute error criteria $icode eabs$$ are enforced during each step of the -integration of the ordinary differential equations. -In addition, they are inversely scaled by the step size so that -the total error bound is less than the sum of the error bounds. -To be specific, if $latex \tilde{X} (t)$$ is the approximate solution -at time $latex t$$, -$icode ta$$ is the initial step time, -and $icode tb$$ is the final step time, -$latex \[ -\left| \tilde{X} (tb)_j - X (tb)_j \right| -\leq -\frac{tf - ti}{tb - ta} -\left[ eabs[j] + erel \; | \tilde{X} (tb)_j | \right] -\] $$ -If $latex X(tb)_j$$ is near zero for some $latex tb \in [ti , tf]$$, -and one uses an absolute error criteria $latex eabs[j]$$ of zero, -the error criteria above will force $code OdeGearControl$$ -to use step sizes equal to -$cref/smin/OdeGearControl/smin/$$ -for steps ending near $latex tb$$. -In this case, the error relative to $icode maxabs$$ can be judged after -$code OdeGearControl$$ returns. -If $icode ef$$ is to large relative to $icode maxabs$$, -$code OdeGearControl$$ can be called again -with a smaller value of $icode smin$$. - -$head Scalar$$ -The type $icode Scalar$$ must satisfy the conditions -for a $cref NumericType$$ type. -The routine $cref CheckNumericType$$ will generate an error message -if this is not the case. -In addition, the following operations must be defined for -$icode Scalar$$ objects $icode a$$ and $icode b$$: - -$table -$bold Operation$$ $cnext $bold Description$$ $rnext -$icode%a% <= %b%$$ $cnext - returns true (false) if $icode a$$ is less than or equal - (greater than) $icode b$$. -$rnext -$icode%a% == %b%$$ $cnext - returns true (false) if $icode a$$ is equal to $icode b$$. -$rnext -$codei%log(%a%)%$$ $cnext - returns a $icode Scalar$$ equal to the logarithm of $icode a$$ -$rnext -$codei%exp(%a%)%$$ $cnext - returns a $icode Scalar$$ equal to the exponential of $icode a$$ -$tend - - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type Scalar/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Example$$ -$children% - example/ode_gear_control.cpp -%$$ -The file -$cref ode_gear_control.cpp$$ -contains an example and test a test of using this routine. -It returns true if it succeeds and false otherwise. - -$head Theory$$ -Let $latex e(s)$$ be the error as a function of the -step size $latex s$$ and suppose that there is a constant -$latex K$$ such that $latex e(s) = K s^m$$. -Let $latex a$$ be our error bound. -Given the value of $latex e(s)$$, a step of size $latex \lambda s$$ -would be ok provided that -$latex \[ -\begin{array}{rcl} - a & \geq & e( \lambda s ) (tf - ti) / ( \lambda s ) \\ - a & \geq & K \lambda^m s^m (tf - ti) / ( \lambda s ) \\ - a & \geq & \lambda^{m-1} s^{m-1} (tf - ti) e(s) / s^m \\ - a & \geq & \lambda^{m-1} (tf - ti) e(s) / s \\ - \lambda^{m-1} & \leq & \frac{a}{e(s)} \frac{s}{tf - ti} -\end{array} -\] $$ -Thus if the right hand side of the last inequality is greater -than or equal to one, the step of size $latex s$$ is ok. - -$head Source Code$$ -The source code for this routine is in the file -$code cppad/ode_gear_control.hpp$$. - -$end --------------------------------------------------------------------------- -*/ - -// link exp and log for float and double -# include - -# include - -namespace CppAD { // Begin CppAD namespace - -template -Vector OdeGearControl( - Fun &F , - size_t M , - const Scalar &ti , - const Scalar &tf , - const Vector &xi , - const Scalar &smin , - const Scalar &smax , - Scalar &sini , - const Vector &eabs , - const Scalar &erel , - Vector &ef , - Vector &maxabs, - size_t &nstep ) -{ - // check simple vector class specifications - CheckSimpleVector(); - - // dimension of the state space - size_t n = size_t(xi.size()); - - CPPAD_ASSERT_KNOWN( - M >= 1, - "Error in OdeGearControl: M is less than one" - ); - CPPAD_ASSERT_KNOWN( - smin <= smax, - "Error in OdeGearControl: smin is greater than smax" - ); - CPPAD_ASSERT_KNOWN( - sini <= smax, - "Error in OdeGearControl: sini is greater than smax" - ); - CPPAD_ASSERT_KNOWN( - size_t(eabs.size()) == n, - "Error in OdeGearControl: size of eabs is not equal to n" - ); - CPPAD_ASSERT_KNOWN( - size_t(maxabs.size()) == n, - "Error in OdeGearControl: size of maxabs is not equal to n" - ); - - // some constants - const Scalar zero(0); - const Scalar one(1); - const Scalar one_plus( Scalar(3) / Scalar(2) ); - const Scalar two(2); - const Scalar ten(10); - - // temporary indices - size_t i, k; - - // temporary Scalars - Scalar step, sprevious, lambda, axi, a, root, r; - - // vectors of Scalars - Vector T (M + 1); - Vector X( (M + 1) * n ); - Vector e(n); - Vector xf(n); - - // initial integer values - size_t m = 1; - nstep = 0; - - // initialize T - T[0] = ti; - - // initialize X, ef, maxabs - for(i = 0; i < n; i++) - for(i = 0; i < n; i++) - { X[i] = xi[i]; - ef[i] = zero; - X[i] = xi[i]; - if( zero <= xi[i] ) - maxabs[i] = xi[i]; - else maxabs[i] = - xi[i]; - - } - - // initial step size - step = smin; - - while( T[m-1] < tf ) - { sprevious = step; - - // check maximum - if( smax <= step ) - step = smax; - - // check minimum - if( m < M ) - { if( step <= sini ) - step = sini; - } - else if( step <= smin ) - step = smin; - - // check if near the end - if( tf <= T[m-1] + one_plus * step ) - T[m] = tf; - else T[m] = T[m-1] + step; - - // try using this step size - nstep++; - OdeGear(F, m, n, T, X, e); - step = T[m] - T[m-1]; - - // compute value of lambda for this step - lambda = Scalar(10) * sprevious / step; - for(i = 0; i < n; i++) - { axi = X[m * n + i]; - if( axi <= zero ) - axi = - axi; - a = eabs[i] + erel * axi; - if( e[i] > zero ) - { if( m == 1 ) - root = (a / e[i]) / ten; - else - { r = ( a / e[i] ) * step / (tf - ti); - root = exp( log(r) / Scalar(m-1) ); - } - if( root <= lambda ) - lambda = root; - } - } - - bool advance; - if( m == M ) - advance = one <= lambda || step <= one_plus * smin; - else advance = one <= lambda || step <= one_plus * sini; - - - if( advance ) - { // accept the results of this time step - CPPAD_ASSERT_UNKNOWN( m <= M ); - if( m == M ) - { // shift for next step - for(k = 0; k < m; k++) - { T[k] = T[k+1]; - for(i = 0; i < n; i++) - X[k*n + i] = X[(k+1)*n + i]; - } - } - // update ef and maxabs - for(i = 0; i < n; i++) - { ef[i] = ef[i] + e[i]; - axi = X[m * n + i]; - if( axi <= zero ) - axi = - axi; - if( axi > maxabs[i] ) - maxabs[i] = axi; - } - if( m != M ) - m++; // all we need do in this case - } - - // new step suggested by error criteria - step = std::min(lambda , ten) * step / two; - } - for(i = 0; i < n; i++) - xf[i] = X[(m-1) * n + i]; - - return xf; -} - -} // End CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/omp_alloc.hpp b/ct_core/include/ct/external/cppad/utility/omp_alloc.hpp deleted file mode 100644 index 6c484d166..000000000 --- a/ct_core/include/ct/external/cppad/utility/omp_alloc.hpp +++ /dev/null @@ -1,783 +0,0 @@ -// $Id: omp_alloc.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_OMP_ALLOC_HPP -# define CPPAD_OMP_ALLOC_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -# include -# ifdef _OPENMP -# include -# endif - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -class omp_alloc{ -// ============================================================================ -public: -/* -$begin omp_max_num_threads$$ -$spell - cppad.hpp - inv - CppAD - num - omp_alloc -$$ -$section Set and Get Maximum Number of Threads for omp_alloc Allocator$$ - -$head Deprecated 2011-08-31$$ -Use the functions $cref/thread_alloc::parallel_setup/ta_parallel_setup/$$ -and $cref/thread_alloc:num_threads/ta_num_threads/$$ instead. - -$head Syntax$$ -$codei%# include -%$$ -$codei%omp_alloc::set_max_num_threads(%number%) -%$$ -$icode%number% = omp_alloc::get_max_num_threads() -%$$ - -$head Purpose$$ -By default there is only one thread and all execution is in sequential mode -(not $cref/parallel/omp_in_parallel/$$). - -$head number$$ -The argument and return value $icode number$$ has prototype -$codei% - size_t %number% -%$$ -and must be greater than zero. - -$head set_max_num_threads$$ -Informs $cref omp_alloc$$ of the maximum number of OpenMP threads. - -$head get_max_num_threads$$ -Returns the valued used in the previous call to $code set_max_num_threads$$. -If there was no such previous call, the value one is returned -(and only thread number zero can use $cref omp_alloc$$). - -$head Restrictions$$ -The function $code set_max_num_threads$$ must be called before -the program enters $cref/parallel/omp_in_parallel/$$ execution mode. -In addition, this function cannot be called while in parallel mode. - -$end -*/ - /*! - Inform omp_alloc of the maximum number of OpenMP threads and enable - parallel execution mode by initializing all statics in this file. - - \param number [in] - maximum number of OpenMP threads. - */ - static void set_max_num_threads(size_t number) - { thread_alloc::parallel_setup( - number, omp_alloc::in_parallel, omp_alloc::get_thread_num - ); - thread_alloc::hold_memory(number > 1); - } - /*! - Get the current maximum number of OpenMP threads that omp_alloc can use. - - \return - maximum number of OpenMP threads. - */ - static size_t get_max_num_threads(void) - { return thread_alloc::num_threads(); } - -/* ----------------------------------------------------------------------- -$begin omp_in_parallel$$ - -$section Is The Current Execution in OpenMP Parallel Mode$$ -$mindex in_parallel$$ -$spell - cppad.hpp - omp_alloc - bool -$$ - -$head Deprecated 2011-08-31$$ -Use the function $cref/thread_alloc::in_parallel/ta_in_parallel/$$ instead. - -$head Syntax$$ -$codei%# include -%$$ -$icode%flag% = omp_alloc::in_parallel()%$$ - -$head Purpose$$ -Some of the $cref omp_alloc$$ allocation routines have different -specifications for parallel (not sequential) execution mode. -This routine enables you to determine if the current execution mode -is sequential or parallel. - -$head flag$$ -The return value has prototype -$codei% - bool %flag% -%$$ -It is true if the current execution is in parallel mode -(possibly multi-threaded) and false otherwise (sequential mode). - -$head Example$$ -$cref omp_alloc.cpp$$ - -$end -*/ - /// Are we in a parallel execution state; i.e., is it possible that - /// other threads are currently executing. - static bool in_parallel(void) - { -# ifdef _OPENMP - return omp_in_parallel() != 0; -# else - return false; -# endif - } - -/* ----------------------------------------------------------------------- -$begin omp_get_thread_num$$ -$spell - cppad.hpp - CppAD - num - omp_alloc - cppad.hpp -$$ - -$section Get the Current OpenMP Thread Number$$ -$mindex get_thread_num$$ - -$head Deprecated 2011-08-31$$ -Use the function $cref/thread_alloc::thread_num/ta_thread_num/$$ instead. - -$head Syntax$$ -$codei%# include -%$$ -$icode%thread% = omp_alloc::get_thread_num()%$$ - -$head Purpose$$ -Some of the $cref omp_alloc$$ allocation routines have a thread number. -This routine enables you to determine the current thread. - -$head thread$$ -The return value $icode thread$$ has prototype -$codei% - size_t %thread% -%$$ -and is the currently executing thread number. -If $code _OPENMP$$ is not defined, $icode thread$$ is zero. - -$head Example$$ -$cref omp_alloc.cpp$$ - -$end -*/ - /// Get current OpenMP thread number (zero if _OpenMP not defined). - static size_t get_thread_num(void) - { -# ifdef _OPENMP - size_t thread = static_cast( omp_get_thread_num() ); - return thread; -# else - return 0; -# endif - } -/* ----------------------------------------------------------------------- -$begin omp_get_memory$$ -$spell - cppad.hpp - num - ptr - omp_alloc -$$ - -$section Get At Least A Specified Amount of Memory$$ - -$head Deprecated 2011-08-31$$ -Use the function $cref/thread_alloc::get_memory/ta_get_memory/$$ instead. - -$head Syntax$$ -$codei%# include -%$$ -$icode%v_ptr% = omp_alloc::get_memory(%min_bytes%, %cap_bytes%)%$$ - -$head Purpose$$ -Use $cref omp_alloc$$ to obtain a minimum number of bytes of memory -(for use by the $cref/current thread/omp_get_thread_num/$$). - -$head min_bytes$$ -This argument has prototype -$codei% - size_t %min_bytes% -%$$ -It specifies the minimum number of bytes to allocate. - -$head cap_bytes$$ -This argument has prototype -$codei% - size_t& %cap_bytes% -%$$ -It's input value does not matter. -Upon return, it is the actual number of bytes (capacity) -that have been allocated for use, -$codei% - %min_bytes% <= %cap_bytes% -%$$ - -$head v_ptr$$ -The return value $icode v_ptr$$ has prototype -$codei% - void* %v_ptr% -%$$ -It is the location where the $icode cap_bytes$$ of memory -that have been allocated for use begins. - -$head Allocation Speed$$ -This allocation should be faster if the following conditions hold: -$list number$$ -The memory allocated by a previous call to $code get_memory$$ -is currently available for use. -$lnext -The current $icode min_bytes$$ is between -the previous $icode min_bytes$$ and previous $icode cap_bytes$$. -$lend - -$head Example$$ -$cref omp_alloc.cpp$$ - -$end -*/ - /*! - Use omp_alloc to get a specified amount of memory. - - If the memory allocated by a previous call to \c get_memory is now - avaialable, and \c min_bytes is between its previous value - and the previous \c cap_bytes, this memory allocation will have - optimal speed. Otherwise, the memory allocation is more complicated and - may have to wait for other threads to complete an allocation. - - \param min_bytes [in] - The minimum number of bytes of memory to be obtained for use. - - \param cap_bytes [out] - The actual number of bytes of memory obtained for use. - - \return - pointer to the beginning of the memory allocted for use. - */ - static void* get_memory(size_t min_bytes, size_t& cap_bytes) - { return thread_alloc::get_memory(min_bytes, cap_bytes); } - -/* ----------------------------------------------------------------------- -$begin omp_return_memory$$ -$spell - cppad.hpp - ptr - omp_alloc -$$ - -$section Return Memory to omp_alloc$$ -$mindex return_memory$$ - -$head Deprecated 2011-08-31$$ -Use the function $cref/thread_alloc::return_memory/ta_return_memory/$$ instead. - -$head Syntax$$ -$codei%# include -%$$ -$codei%omp_alloc::return_memory(%v_ptr%)%$$ - -$head Purpose$$ -If $cref omp_max_num_threads$$ is one, -the memory is returned to the system. -Otherwise, the memory is retained by $cref omp_alloc$$ for quick future use -by the thread that allocated to memory. - -$head v_ptr$$ -This argument has prototype -$codei% - void* %v_ptr% -%$$. -It must be a pointer to memory that is currently in use; i.e. -obtained by a previous call to $cref omp_get_memory$$ and not yet returned. - -$head Thread$$ -Either the $cref/current thread/omp_get_thread_num/$$ must be the same as during -the corresponding call to $cref omp_get_memory$$, -or the current execution mode must be sequential -(not $cref/parallel/omp_in_parallel/$$). - -$head NDEBUG$$ -If $code NDEBUG$$ is defined, $icode v_ptr$$ is not checked (this is faster). -Otherwise, a list of in use pointers is searched to make sure -that $icode v_ptr$$ is in the list. - -$head Example$$ -$cref omp_alloc.cpp$$ - -$end -*/ - /*! - Return memory that was obtained by \c get_memory. - If max_num_threads(0) == 1, - the memory is returned to the system. - Otherwise, it is retained by \c omp_alloc and available for use by - \c get_memory for this thread. - - \param v_ptr [in] - Value of the pointer returned by \c get_memory and still in use. - After this call, this pointer will available (and not in use). - - \par - We must either be in sequential (not parallel) execution mode, - or the current thread must be the same as for the corresponding call - to \c get_memory. - */ - static void return_memory(void* v_ptr) - { thread_alloc::return_memory(v_ptr); } -/* ----------------------------------------------------------------------- -$begin omp_free_available$$ -$spell - cppad.hpp - omp_alloc -$$ - -$section Free Memory Currently Available for Quick Use by a Thread$$ -$mindex free_available$$ - -$head Deprecated 2011-08-31$$ -Use the function $cref/thread_alloc::free_available/ta_free_available/$$ -instead. - -$head Syntax$$ -$codei%# include -%$$ -$codei%omp_alloc::free_available(%thread%)%$$ - -$head Purpose$$ -Free memory, currently available for quick use by a specific thread, -for general future use. - -$head thread$$ -This argument has prototype -$codei% - size_t %thread% -%$$ -Either $cref omp_get_thread_num$$ must be the same as $icode thread$$, -or the current execution mode must be sequential -(not $cref/parallel/omp_in_parallel/$$). - -$head Example$$ -$cref omp_alloc.cpp$$ - -$end -*/ - /*! - Return all the memory being held as available for a thread to the system. - - \param thread [in] - this thread that will no longer have any available memory after this call. - This must either be the thread currently executing, or we must be - in sequential (not parallel) execution mode. - */ - static void free_available(size_t thread) - { thread_alloc::free_available(thread); } -/* ----------------------------------------------------------------------- -$begin omp_inuse$$ -$spell - cppad.hpp - num - inuse - omp_alloc -$$ - -$section Amount of Memory a Thread is Currently Using$$ -$mindex inuse$$ - -$head Deprecated 2011-08-31$$ - -$head Syntax$$ -$codei%# include -%$$ -$icode%num_bytes% = omp_alloc::inuse(%thread%)%$$ -Use the function $cref/thread_alloc::inuse/ta_inuse/$$ instead. - -$head Purpose$$ -Memory being managed by $cref omp_alloc$$ has two states, -currently in use by the specified thread, -and quickly available for future use by the specified thread. -This function informs the program how much memory is in use. - -$head thread$$ -This argument has prototype -$codei% - size_t %thread% -%$$ -Either $cref omp_get_thread_num$$ must be the same as $icode thread$$, -or the current execution mode must be sequential -(not $cref/parallel/omp_in_parallel/$$). - -$head num_bytes$$ -The return value has prototype -$codei% - size_t %num_bytes% -%$$ -It is the number of bytes currently in use by the specified thread. - -$head Example$$ -$cref omp_alloc.cpp$$ - -$end -*/ - /*! - Determine the amount of memory that is currently inuse. - - \param thread [in] - Thread for which we are determining the amount of memory - (must be < CPPAD_MAX_NUM_THREADS). - Durring parallel execution, this must be the thread - that is currently executing. - - \return - The amount of memory in bytes. - */ - static size_t inuse(size_t thread) - { return thread_alloc::inuse(thread); } -/* ----------------------------------------------------------------------- -$begin omp_available$$ -$spell - cppad.hpp - num - omp_alloc -$$ - -$section Amount of Memory Available for Quick Use by a Thread$$ - -$head Deprecated 2011-08-31$$ -Use the function $cref/thread_alloc::available/ta_available/$$ instead. - -$head Syntax$$ -$codei%# include -%$$ -$icode%num_bytes% = omp_alloc::available(%thread%)%$$ - -$head Purpose$$ -Memory being managed by $cref omp_alloc$$ has two states, -currently in use by the specified thread, -and quickly available for future use by the specified thread. -This function informs the program how much memory is available. - -$head thread$$ -This argument has prototype -$codei% - size_t %thread% -%$$ -Either $cref omp_get_thread_num$$ must be the same as $icode thread$$, -or the current execution mode must be sequential -(not $cref/parallel/omp_in_parallel/$$). - -$head num_bytes$$ -The return value has prototype -$codei% - size_t %num_bytes% -%$$ -It is the number of bytes currently available for use by the specified thread. - -$head Example$$ -$cref omp_alloc.cpp$$ - -$end -*/ - /*! - Determine the amount of memory that is currently available for use. - - \copydetails inuse - */ - static size_t available(size_t thread) - { return thread_alloc::available(thread); } -/* ----------------------------------------------------------------------- -$begin omp_create_array$$ -$spell - cppad.hpp - omp_alloc - sizeof -$$ - -$section Allocate Memory and Create A Raw Array$$ -$mindex create_array$$ - -$head Deprecated 2011-08-31$$ -Use the function $cref/thread_alloc::create_array/ta_create_array/$$ instead. - -$head Syntax$$ -$codei%# include -%$$ -$icode%array% = omp_alloc::create_array<%Type%>(%size_min%, %size_out%)%$$. - -$head Purpose$$ -Create a new raw array using $cref omp_alloc$$ a fast memory allocator -that works well in a multi-threading OpenMP environment. - -$head Type$$ -The type of the elements of the array. - -$head size_min$$ -This argument has prototype -$codei% - size_t %size_min% -%$$ -This is the minimum number of elements that there can be -in the resulting $icode array$$. - -$head size_out$$ -This argument has prototype -$codei% - size_t& %size_out% -%$$ -The input value of this argument does not matter. -Upon return, it is the actual number of elements -in $icode array$$ -($icode% size_min %<=% size_out%$$). - -$head array$$ -The return value $icode array$$ has prototype -$codei% - %Type%* %array% -%$$ -It is array with $icode size_out$$ elements. -The default constructor for $icode Type$$ is used to initialize the -elements of $icode array$$. -Note that $cref omp_delete_array$$ -should be used to destroy the array when it is no longer needed. - -$head Delta$$ -The amount of memory $cref omp_inuse$$ by the current thread, -will increase $icode delta$$ where -$codei% - sizeof(%Type%) * (%size_out% + 1) > %delta% >= sizeof(%Type%) * %size_out% -%$$ -The $cref omp_available$$ memory will decrease by $icode delta$$, -(and the allocation will be faster) -if a previous allocation with $icode size_min$$ between its current value -and $icode size_out$$ is available. - -$head Example$$ -$cref omp_alloc.cpp$$ - -$end -*/ - /*! - Use omp_alloc to Create a Raw Array. - - \tparam Type - The type of the elements of the array. - - \param size_min [in] - The minimum number of elements in the array. - - \param size_out [out] - The actual number of elements in the array. - - \return - pointer to the first element of the array. - The default constructor is used to initialize - all the elements of the array. - - \par - The \c extra_ field, in the \c omp_alloc node before the return value, - is set to size_out. - */ - template - static Type* create_array(size_t size_min, size_t& size_out) - { return thread_alloc::create_array(size_min, size_out); } -/* ----------------------------------------------------------------------- -$begin omp_delete_array$$ -$spell - cppad.hpp - omp_alloc - sizeof -$$ - -$section Return A Raw Array to The Available Memory for a Thread$$ -$mindex delete_array$$ - -$head Deprecated 2011-08-31$$ -Use the function $cref/thread_alloc::delete_array/ta_delete_array/$$ instead. - -$head Syntax$$ -$codei%# include -%$$ -$codei%omp_alloc::delete_array(%array%)%$$. - -$head Purpose$$ -Returns memory corresponding to a raw array -(create by $cref omp_create_array$$) to the -$cref omp_available$$ memory pool for the current thread. - -$head Type$$ -The type of the elements of the array. - -$head array$$ -The argument $icode array$$ has prototype -$codei% - %Type%* %array% -%$$ -It is a value returned by $cref omp_create_array$$ and not yet deleted. -The $icode Type$$ destructor is called for each element in the array. - -$head Thread$$ -The $cref/current thread/omp_get_thread_num/$$ must be the -same as when $cref omp_create_array$$ returned the value $icode array$$. -There is an exception to this rule: -when the current execution mode is sequential -(not $cref/parallel/omp_in_parallel/$$) the current thread number does not matter. - -$head Delta$$ -The amount of memory $cref omp_inuse$$ will decrease by $icode delta$$, -and the $cref omp_available$$ memory will increase by $icode delta$$, -where $cref/delta/omp_create_array/Delta/$$ -is the same as for the corresponding call to $code create_array$$. - -$head Example$$ -$cref omp_alloc.cpp$$ - -$end -*/ - /*! - Return Memory Used for a Raw Array to the Available Pool. - - \tparam Type - The type of the elements of the array. - - \param array [in] - A value returned by \c create_array that has not yet been deleted. - The \c Type destructor is used to destroy each of the elements - of the array. - - \par - Durring parallel execution, the current thread must be the same - as during the corresponding call to \c create_array. - */ - template - static void delete_array(Type* array) - { thread_alloc::delete_array(array); } -}; -/* -------------------------------------------------------------------------- -$begin omp_efficient$$ -$spell - cppad.hpp - omp_alloc - ptr - num - bool - const -$$ - -$section Check If A Memory Allocation is Efficient for Another Use$$ - -$head Removed$$ -This function has been removed because speed tests seem to indicate -it is just as fast, or faster, to free and then reallocate the memory. - -$head Syntax$$ -$codei%# include -%$$ -$icode%flag% = omp_alloc::efficient(%v_ptr%, %num_bytes%)%$$ - -$head Purpose$$ -Check if memory that is currently in use is an efficient -allocation for a specified number of bytes. - -$head v_ptr$$ -This argument has prototype -$codei% - const void* %v_ptr% -%$$. -It must be a pointer to memory that is currently in use; i.e. -obtained by a previous call to $cref omp_get_memory$$ and not yet returned. - -$head num_bytes$$ -This argument has prototype -$codei% - size_t %num_bytes% -%$$ -It specifies the number of bytes of the memory allocated by $icode v_ptr$$ -that we want to use. - -$head flag$$ -The return value has prototype -$codei% - bool %flag% -%$$ -It is true, -a call to $code get_memory$$ with -$cref/min_bytes/omp_get_memory/min_bytes/$$ -equal to $icode num_bytes$$ would result in a value for -$cref/cap_bytes/omp_get_memory/cap_bytes/$$ that is the same as when $code v_ptr$$ -was returned by $code get_memory$$; i.e., -$icode v_ptr$$ is an efficient memory block for $icode num_bytes$$ -bytes of information. - -$head Thread$$ -Either the $cref/current thread/omp_get_thread_num/$$ must be the same as during -the corresponding call to $cref omp_get_memory$$, -or the current execution mode must be sequential -(not $cref/parallel/omp_in_parallel/$$). - -$head NDEBUG$$ -If $code NDEBUG$$ is defined, $icode v_ptr$$ is not checked (this is faster). -Otherwise, a list of in use pointers is searched to make sure -that $icode v_ptr$$ is in the list. - -$end ---------------------------------------------------------------------------- -$begin old_max_num_threads$$ -$spell - cppad.hpp - inv - CppAD - num - omp_alloc -$$ -$section Set Maximum Number of Threads for omp_alloc Allocator$$ -$mindex max_num_threads$$ - -$head Removed$$ -This function has been removed from the CppAD API. -Use the function $cref/thread_alloc::parallel_setup/ta_parallel_setup/$$ -in its place. - -$head Syntax$$ -$codei%# include -%$$ -$codei%omp_alloc::max_num_threads(%number%)%$$ - -$head Purpose$$ -By default there is only one thread and all execution is in sequential mode -(not $cref/parallel/omp_in_parallel/$$). - -$head number$$ -The argument $icode number$$ has prototype -$codei% - size_t %number% -%$$ -It must be greater than zero and specifies the maximum number of -OpenMP threads that will be active at one time. - -$head Restrictions$$ -This function must be called before the program enters -$cref/parallel/omp_in_parallel/$$ execution mode. - -$end -------------------------------------------------------------------------------- -*/ -} // END_CPPAD_NAMESPACE - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/poly.hpp b/ct_core/include/ct/external/cppad/utility/poly.hpp deleted file mode 100644 index 23e176509..000000000 --- a/ct_core/include/ct/external/cppad/utility/poly.hpp +++ /dev/null @@ -1,194 +0,0 @@ -// $Id: poly.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_POLY_HPP -# define CPPAD_POLY_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin Poly$$ -$spell - cppad.hpp - CppAD - namespace - cstddef - ifndef - endif - deg - const - std - da -$$ - - -$section Evaluate a Polynomial or its Derivative$$ -$mindex Poly template$$ - -$head Syntax$$ -$codei%# include -%$$ -$icode%p% = Poly(%k%, %a%, %z%)%$$ - - -$head Description$$ -Computes the $th k$$ derivative of the polynomial -$latex \[ - P(z) = a_0 + a_1 z^1 + \cdots + a_d z^d -\] $$ -If $icode k$$ is equal to zero, the return value is $latex P(z)$$. - -$head Include$$ -The file $code cppad/poly.hpp$$ is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of -the $code CppAD$$ routines. -Including this file defines -$code Poly$$ within the $code CppAD$$ namespace. - -$head k$$ -The argument $icode k$$ has prototype -$codei% - size_t %k% -%$$ -It specifies the order of the derivative to calculate. - -$head a$$ -The argument $icode a$$ has prototype -$codei% - const %Vector% &%a% -%$$ -(see $cref/Vector/Poly/Vector/$$ below). -It specifies the vector corresponding to the polynomial $latex P(z)$$. - -$head z$$ -The argument $icode z$$ has prototype -$codei% - const %Type% &%z% -%$$ -(see $icode Type$$ below). -It specifies the point at which to evaluate the polynomial - -$head p$$ -The result $icode p$$ has prototype -$codei% - %Type% %p% -%$$ -(see $cref/Type/Poly/Type/$$ below) -and it is equal to the $th k$$ derivative of $latex P(z)$$; i.e., -$latex \[ -p = \frac{k !}{0 !} a_k - + \frac{(k+1) !}{1 !} a_{k+1} z^1 - + \ldots - + \frac{d !}{(d - k) !} a_d z^{d - k} -\] -$$ -If $latex k > d$$, $icode%p% = %Type%(0)%$$. - -$head Type$$ -The type $icode Type$$ is determined by the argument $icode z$$. -It is assumed that -multiplication and addition of $icode Type$$ objects -are commutative. - -$subhead Operations$$ -The following operations must be supported where -$icode x$$ and $icode y$$ are objects of type $icode Type$$ -and $icode i$$ is an $code int$$: -$table -$icode%x% = %i%$$ $cnext assignment $rnext -$icode%x% = %y%$$ $cnext assignment $rnext -$icode%x% *= %y%$$ $cnext multiplication computed assignment $rnext -$icode%x% += %y%$$ $cnext addition computed assignment - -$tend - - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type/SimpleVector/Elements of Specified Type/$$ -$icode Type$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Operation Sequence$$ -The $icode Type$$ operation sequence used to calculate $icode p$$ is -$cref/independent/glossary/Operation/Independent/$$ -of $icode z$$ and the elements of $icode a$$ -(it does depend on the size of the vector $icode a$$). - - -$children% - example/poly.cpp% - omh/poly_hpp.omh -%$$ - -$head Example$$ -The file -$cref poly.cpp$$ -contains an example and test of this routine. -It returns true if it succeeds and false otherwise. - -$head Source$$ -The file $cref poly.hpp$$ contains the -current source code that implements these specifications. - -$end ------------------------------------------------------------------------------- -*/ -// BEGIN C++ -# include // used to defined size_t -# include - -namespace CppAD { // BEGIN CppAD namespace - -template -Type Poly(size_t k, const Vector &a, const Type &z) -{ size_t i; - size_t d = a.size() - 1; - - Type tmp; - - // check Vector is Simple Vector class with Type elements - CheckSimpleVector(); - - // case where derivative order greater than degree of polynomial - if( k > d ) - { tmp = 0; - return tmp; - } - // case where we are evaluating a derivative - if( k > 0 ) - { // initialize factor as (k-1) ! - size_t factor = 1; - for(i = 2; i < k; i++) - factor *= i; - - // set b to coefficient vector corresponding to derivative - Vector b(d - k + 1); - for(i = k; i <= d; i++) - { factor *= i; - tmp = factor; - b[i - k] = a[i] * tmp; - factor /= (i - k + 1); - } - // value of derivative polynomial - return Poly(0, b, z); - } - // case where we are evaluating the original polynomial - Type sum = a[d]; - i = d; - while(i > 0) - { sum *= z; - sum += a[--i]; - } - return sum; -} -} // END CppAD namespace -// END C++ -# endif diff --git a/ct_core/include/ct/external/cppad/utility/pow_int.hpp b/ct_core/include/ct/external/cppad/utility/pow_int.hpp deleted file mode 100644 index dbb29cfb4..000000000 --- a/ct_core/include/ct/external/cppad/utility/pow_int.hpp +++ /dev/null @@ -1,142 +0,0 @@ -// $Id: pow_int.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_POW_INT_HPP -# define CPPAD_POW_INT_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -------------------------------------------------------------------------------- -$begin pow_int$$ -$spell - cppad.hpp - CppAD - namespace - const -$$ - - -$section The Integer Power Function$$ -$mindex pow exponent$$ - -$head Syntax$$ -$codei%# include -%$$ -$icode%z% = pow(%x%, %y%)%$$ - -$head See Also$$ -$cref pow$$ - -$head Purpose$$ -Determines the value of the power function -$latex \[ - {\rm pow} (x, y) = x^y -\] $$ -for integer exponents $icode n$$ -using multiplication and possibly division to compute the value. -The other CppAD $cref pow$$ function may use logarithms and exponentiation -to compute derivatives of the same value -(which will not work if $icode x$$ is less than or equal zero). - -$head Include$$ -The file $code cppad/pow_int.h$$ is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of -the $code CppAD$$ routines. -Including this file defines -this version of the $code pow$$ within the $code CppAD$$ namespace. - -$head x$$ -The argument $icode x$$ has prototype -$codei% - const %Type%& %x% -%$$ - -$head y$$ -The argument $icode y$$ has prototype -$codei% - const int& %y% -%$$ - -$head z$$ -The result $icode z$$ has prototype -$codei% - %Type% %z% -%$$ - -$head Type$$ -The type $icode Type$$ must support the following operations -where $icode a$$ and $icode b$$ are $icode Type$$ objects -and $icode i$$ is an $code int$$: -$table -$bold Operation$$ $pre $$ - $cnext $bold Description$$ - $cnext $bold Result Type$$ -$rnext -$icode%Type% %a%(%i%)%$$ - $cnext construction of a $icode Type$$ object from an $code int$$ - $cnext $icode Type$$ -$rnext -$icode%a% * %b%$$ - $cnext binary multiplication of $icode Type$$ objects - $cnext $icode Type$$ -$rnext -$icode%a% / %b%$$ - $cnext binary division of $icode Type$$ objects - $cnext $icode Type$$ -$tend - -$head Operation Sequence$$ -The $icode Type$$ operation sequence used to calculate $icode z$$ is -$cref/independent/glossary/Operation/Independent/$$ -of $icode x$$. - -$head Example$$ -$children% - example/pow_int.cpp -%$$ -The file $cref pow_int.cpp$$ -is an example and test of this function. -It returns true if it succeeds and false otherwise. - - -$end -------------------------------------------------------------------------------- -*/ - -namespace CppAD { - - template - inline Type pow (const Type& x, const int& n) - { - Type p(1); - int n2 = n / 2; - - if( n == 0 ) - return p; - if( n < 0 ) - return p / pow(x, -n); - if( n == 1 ) - return x; - - // p = (x^2)^(n/2) - p = pow( x * x , n2 ); - - // n is even case - if( n % 2 == 0 ) - return p; - - // n is odd case - return p * x; - } - -} - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/romberg_mul.hpp b/ct_core/include/ct/external/cppad/utility/romberg_mul.hpp deleted file mode 100644 index b307e47a4..000000000 --- a/ct_core/include/ct/external/cppad/utility/romberg_mul.hpp +++ /dev/null @@ -1,327 +0,0 @@ -// $Id: romberg_mul.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_ROMBERG_MUL_HPP -# define CPPAD_ROMBERG_MUL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin RombergMul$$ -$spell - cppad.hpp - bool - const - Cpp - RombergMulMul -$$ - -$section Multi-dimensional Romberg Integration$$ -$mindex integrate multi dimensional dimension$$ - - -$head Syntax$$ -$codei%# include -%$$ -$codei%RombergMul<%Fun%, %SizeVector%, %FloatVector%, %m%> %R%$$ -$pre -$$ -$icode%r% = %R%(%F%, %a%, %b%, %n%, %p%, %e%)%$$ - - -$head Description$$ -Returns the Romberg integration estimate -$latex r$$ for the multi-dimensional integral -$latex \[ -r = -\int_{a[0]}^{b[0]} \cdots \int_{a[m-1]}^{b[m-1]} -\; F(x) \; -{\bf d} x_0 \cdots {\bf d} x_{m-1} -\; + \; -\sum_{i=0}^{m-1} -O \left[ ( b[i] - a[i] ) / 2^{n[i]-1} \right]^{2(p[i]+1)} -\] $$ - -$head Include$$ -The file $code cppad/romberg_mul.hpp$$ is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of -the $code CppAD$$ routines. - -$head m$$ -The template parameter $icode m$$ must be convertible to a $code size_t$$ -object with a value that can be determined at compile time; for example -$code 2$$. -It determines the dimension of the domain space for the integration. - -$head r$$ -The return value $icode r$$ has prototype -$codei% - %Float% %r% -%$$ -It is the estimate computed by $code RombergMul$$ for the integral above -(see description of $cref/Float/RombergMul/Float/$$ below). - -$head F$$ -The object $icode F$$ has the prototype -$codei% - %Fun% &%F% -%$$ -It must support the operation -$codei% - %F%(%x%) -%$$ -The argument $icode x$$ to $icode F$$ has prototype -$codei% - const %Float% &%x% -%$$ -The return value of $icode F$$ is a $icode Float$$ object - -$head a$$ -The argument $icode a$$ has prototype -$codei% - const %FloatVector% &%a% -%$$ -It specifies the lower limit for the integration -(see description of $cref/FloatVector/RombergMul/FloatVector/$$ below). - -$head b$$ -The argument $icode b$$ has prototype -$codei% - const %FloatVector% &%b% -%$$ -It specifies the upper limit for the integration. - -$head n$$ -The argument $icode n$$ has prototype -$codei% - const %SizeVector% &%n% -%$$ -A total number of $latex 2^{n[i]-1} + 1$$ -evaluations of $icode%F%(%x%)%$$ are used to estimate the integral -with respect to $latex {\bf d} x_i$$. - -$head p$$ -The argument $icode p$$ has prototype -$codei% - const %SizeVector% &%p% -%$$ -For $latex i = 0 , \ldots , m-1$$, -$latex n[i]$$ determines the accuracy order in the -approximation for the integral -that is returned by $code RombergMul$$. -The values in $icode p$$ must be less than or equal $icode n$$; i.e., -$icode%p%[%i%] <= %n%[%i%]%$$. - -$head e$$ -The argument $icode e$$ has prototype -$codei% - %Float% &%e% -%$$ -The input value of $icode e$$ does not matter -and its output value is an approximation for the absolute error in -the integral estimate. - -$head Float$$ -The type $icode Float$$ is defined as the type of the elements of -$cref/FloatVector/RombergMul/FloatVector/$$. -The type $icode Float$$ must satisfy the conditions -for a $cref NumericType$$ type. -The routine $cref CheckNumericType$$ will generate an error message -if this is not the case. -In addition, if $icode x$$ and $icode y$$ are $icode Float$$ objects, -$codei% - %x% < %y% -%$$ -returns the $code bool$$ value true if $icode x$$ is less than -$icode y$$ and false otherwise. - -$head FloatVector$$ -The type $icode FloatVector$$ must be a $cref SimpleVector$$ class. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - - -$children% - example/romberg_mul.cpp -%$$ -$head Example$$ -$comment% - example/romberg_mul.cpp -%$$ -The file -$cref Rombergmul.cpp$$ -contains an example and test a test of using this routine. -It returns true if it succeeds and false otherwise. - -$head Source Code$$ -The source code for this routine is in the file -$code cppad/romberg_mul.hpp$$. - -$end -*/ - -# include -# include -# include - -namespace CppAD { // BEGIN CppAD namespace - -template -class SliceLast { - typedef typename FloatVector::value_type Float; -private: - Fun *F; - size_t last; - FloatVector x; -public: - SliceLast( Fun *F_, size_t last_, const FloatVector &x_ ) - : F(F_) , last(last_), x(last + 1) - { size_t i; - for(i = 0; i < last; i++) - x[i] = x_[i]; - } - double operator()(const Float &xlast) - { x[last] = xlast; - return (*F)(x); - } -}; - -template -class IntegrateLast { -private: - Fun *F; - const size_t last; - const FloatVector a; - const FloatVector b; - const SizeVector n; - const SizeVector p; - Float esum; - size_t ecount; - -public: - IntegrateLast( - Fun *F_ , - size_t last_ , - const FloatVector &a_ , - const FloatVector &b_ , - const SizeVector &n_ , - const SizeVector &p_ ) - : F(F_) , last(last_), a(a_) , b(b_) , n(n_) , p(p_) - { } - Float operator()(const FloatVector &x) - { Float r, e; - SliceLast S(F, last, x); - r = CppAD::RombergOne( - S, a[last], b[last], n[last], p[last], e - ); - esum = esum + e; - ecount++; - return r; - } - void ClearEsum(void) - { esum = 0.; } - Float GetEsum(void) - { return esum; } - - void ClearEcount(void) - { ecount = 0; } - size_t GetEcount(void) - { return ecount; } -}; - -template -class RombergMul { - typedef typename FloatVector::value_type Float; -public: - RombergMul(void) - { } - Float operator() ( - Fun &F , - const FloatVector &a , - const FloatVector &b , - const SizeVector &n , - const SizeVector &p , - Float &e ) - { Float r; - - typedef IntegrateLast< - Fun , - SizeVector , - FloatVector , - Float > IntegrateOne; - - IntegrateOne Fm1(&F, m-1, a, b, n, p); - RombergMul< - IntegrateOne, - SizeVector , - FloatVector , - m-1 > RombergMulM1; - - Fm1.ClearEsum(); - Fm1.ClearEcount(); - - r = RombergMulM1(Fm1, a, b, n, p, e); - - size_t i, j; - Float prod = 1; - size_t pow2 = 1; - for(i = 0; i < m-1; i++) - { prod *= (b[i] - a[i]); - for(j = 0; j < (n[i] - 1); j++) - pow2 *= 2; - } - assert( Fm1.GetEcount() == (pow2+1) ); - - e = e + Fm1.GetEsum() * prod / Fm1.GetEcount(); - - return r; - } -}; - -template -class RombergMul { - typedef typename FloatVector::value_type Float; -public: - Float operator() ( - Fun &F , - const FloatVector &a , - const FloatVector &b , - const SizeVector &n , - const SizeVector &p , - Float &e ) - { Float r; - typedef IntegrateLast< - Fun , - SizeVector , - FloatVector , - Float > IntegrateOne; - - // check simple vector class specifications - CheckSimpleVector(); - - // check numeric type specifications - CheckNumericType(); - - IntegrateOne F0(&F, 0, a, b, n, p); - - F0.ClearEsum(); - F0.ClearEcount(); - - r = F0(a); - - assert( F0.GetEcount() == 1 ); - e = F0.GetEsum(); - - return r; - } -}; - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/romberg_one.hpp b/ct_core/include/ct/external/cppad/utility/romberg_one.hpp deleted file mode 100644 index 302addf23..000000000 --- a/ct_core/include/ct/external/cppad/utility/romberg_one.hpp +++ /dev/null @@ -1,215 +0,0 @@ -// $Id: romberg_one.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_ROMBERG_ONE_HPP -# define CPPAD_ROMBERG_ONE_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin RombergOne$$ -$spell - cppad.hpp - bool - const - Cpp - RombergOne -$$ - -$section One DimensionalRomberg Integration$$ -$mindex integrate Romberg$$ - - -$head Syntax$$ -$codei%# include -%$$ -$icode%r% = RombergOne(%F%, %a%, %b%, %n%, %e%)%$$ - - -$head Description$$ -Returns the Romberg integration estimate -$latex r$$ for a one dimensional integral -$latex \[ -r = \int_a^b F(x) {\bf d} x + O \left[ (b - a) / 2^{n-1} \right]^{2(p+1)} -\] $$ - -$head Include$$ -The file $code cppad/romberg_one.hpp$$ is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of -the $code CppAD$$ routines. - -$head r$$ -The return value $icode r$$ has prototype -$codei% - %Float% %r% -%$$ -It is the estimate computed by $code RombergOne$$ for the integral above. - -$head F$$ -The object $icode F$$ can be of any type, but it must support -the operation -$codei% - %F%(%x%) -%$$ -The argument $icode x$$ to $icode F$$ has prototype -$codei% - const %Float% &%x% -%$$ -The return value of $icode F$$ is a $icode Float$$ object -(see description of $cref/Float/RombergOne/Float/$$ below). - -$head a$$ -The argument $icode a$$ has prototype -$codei% - const %Float% &%a% -%$$ -It specifies the lower limit for the integration. - -$head b$$ -The argument $icode b$$ has prototype -$codei% - const %Float% &%b% -%$$ -It specifies the upper limit for the integration. - -$head n$$ -The argument $icode n$$ has prototype -$codei% - size_t %n% -%$$ -A total number of $latex 2^{n-1} + 1$$ evaluations of $icode%F%(%x%)%$$ -are used to estimate the integral. - -$head p$$ -The argument $icode p$$ has prototype -$codei% - size_t %p% -%$$ -It must be less than or equal $latex n$$ -and determines the accuracy order in the approximation for the integral -that is returned by $code RombergOne$$. -To be specific -$latex \[ -r = \int_a^b F(x) {\bf d} x + O \left[ (b - a) / 2^{n-1} \right]^{2(p+1)} -\] $$ - - -$head e$$ -The argument $icode e$$ has prototype -$codei% - %Float% &%e% -%$$ -The input value of $icode e$$ does not matter -and its output value is an approximation for the error in -the integral estimates; i.e., -$latex \[ - e \approx \left| r - \int_a^b F(x) {\bf d} x \right| -\] $$ - -$head Float$$ -The type $icode Float$$ must satisfy the conditions -for a $cref NumericType$$ type. -The routine $cref CheckNumericType$$ will generate an error message -if this is not the case. -In addition, if $icode x$$ and $icode y$$ are $icode Float$$ objects, -$codei% - %x% < %y% -%$$ -returns the $code bool$$ value true if $icode x$$ is less than -$icode y$$ and false otherwise. - -$children% - example/romberg_one.cpp -%$$ -$head Example$$ -$comment% - example/romberg_one.cpp -%$$ -The file -$cref romberg_one.cpp$$ -contains an example and test a test of using this routine. -It returns true if it succeeds and false otherwise. - -$head Source Code$$ -The source code for this routine is in the file -$code cppad/romberg_one.hpp$$. - -$end -*/ - -# include -# include -# include - -namespace CppAD { // BEGIN CppAD namespace - -template -Float RombergOne( - Fun &F , - const Float &a , - const Float &b , - size_t n , - size_t p , - Float &e ) -{ - size_t ipow2 = 1; - size_t k, i; - Float pow2, sum, x; - - Float zero = Float(0); - Float two = Float(2); - - // check specifications for a NumericType - CheckNumericType(); - - CPPAD_ASSERT_KNOWN( - n >= 2, - "RombergOne: n must be greater than or equal 2" - ); - CppAD::vector r(n); - - // set r[i] = trapazoidal rule with 2^i intervals in [a, b] - r[0] = ( F(a) + F(b) ) * (b - a) / two; - for(i = 1; i < n; i++) - { ipow2 *= 2; - // there must be a conversion from int to any numeric type - pow2 = Float(int(ipow2)); - sum = zero; - for(k = 1; k < ipow2; k += 2) - { // start = a + (b-a)/pow2, increment = 2*(b-a)/pow2 - x = ( (pow2 - Float(int(k))) * a + k * b ) / pow2; - sum = sum + F(x); - } - // combine function evaluations in sum with those in T[i-1] - r[i] = r[i-1] / two + sum * (b - a) / pow2; - } - - // now compute the higher order estimates - size_t ipow4 = 1; // order of accuract for previous estimate - Float pow4, pow4minus; - for(i = 0; i < p; i++) - { // compute estimate accurate to O[ step^(2*(i+1)) ] - // put resutls in r[n-1], r[n-2], ... , r[n-i+1] - ipow4 *= 4; - pow4 = Float(int(ipow4)); - pow4minus = Float(ipow4-1); - for(k = n-1; k > i; k--) - r[k] = ( pow4 * r[k] - r[k-1] ) / pow4minus; - } - - // error estimate for r[n] - e = r[n-1] - r[n-2]; - if( e < zero ) - e = - e; - return r[n-1]; -} - -} // END CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/rosen_34.hpp b/ct_core/include/ct/external/cppad/utility/rosen_34.hpp deleted file mode 100644 index cb1668aec..000000000 --- a/ct_core/include/ct/external/cppad/utility/rosen_34.hpp +++ /dev/null @@ -1,498 +0,0 @@ -// $Id: rosen_34.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_ROSEN_34_HPP -# define CPPAD_ROSEN_34_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Rosen34$$ -$spell - cppad.hpp - bool - xf - templated - const - Rosenbrock - CppAD - xi - ti - tf - Karp - Rosen - Shampine - ind - dep -$$ - - -$section A 3rd and 4th Order Rosenbrock ODE Solver$$ -$mindex Rosen34 solve stiff differential equation$$ - -$head Syntax$$ -$codei%# include -%$$ -$icode%xf% = Rosen34(%F%, %M%, %ti%, %tf%, %xi%) -%$$ -$icode%xf% = Rosen34(%F%, %M%, %ti%, %tf%, %xi%, %e%) -%$$ - - -$head Description$$ -This is an embedded 3rd and 4th order Rosenbrock ODE solver -(see Section 16.6 of $cref/Numerical Recipes/Bib/Numerical Recipes/$$ -for a description of Rosenbrock ODE solvers). -In particular, we use the formulas taken from page 100 of -$cref/Shampine, L.F./Bib/Shampine, L.F./$$ -(except that the fraction 98/108 has been correction to be 97/108). -$pre - -$$ -We use $latex n$$ for the size of the vector $icode xi$$. -Let $latex \B{R}$$ denote the real numbers -and let $latex F : \B{R} \times \B{R}^n \rightarrow \B{R}^n$$ be a smooth function. -The return value $icode xf$$ contains a 5th order -approximation for the value $latex X(tf)$$ where -$latex X : [ti , tf] \rightarrow \B{R}^n$$ is defined by -the following initial value problem: -$latex \[ -\begin{array}{rcl} - X(ti) & = & xi \\ - X'(t) & = & F[t , X(t)] -\end{array} -\] $$ -If your set of ordinary differential equations are not stiff -an explicit method may be better (perhaps $cref Runge45$$.) - -$head Include$$ -The file $code cppad/rosen_34.hpp$$ is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of -the $code CppAD$$ routines. - -$head xf$$ -The return value $icode xf$$ has the prototype -$codei% - %Vector% %xf% -%$$ -and the size of $icode xf$$ is equal to $icode n$$ -(see description of $cref/Vector/Rosen34/Vector/$$ below). -$latex \[ - X(tf) = xf + O( h^5 ) -\] $$ -where $latex h = (tf - ti) / M$$ is the step size. -If $icode xf$$ contains not a number $cref nan$$, -see the discussion of $cref/f/Rosen34/Fun/Nan/$$. - -$head Fun$$ -The class $icode Fun$$ -and the object $icode F$$ satisfy the prototype -$codei% - %Fun% &%F% -%$$ -This must support the following set of calls -$codei% - %F%.Ode(%t%, %x%, %f%) - %F%.Ode_ind(%t%, %x%, %f_t%) - %F%.Ode_dep(%t%, %x%, %f_x%) -%$$ - -$subhead t$$ -In all three cases, -the argument $icode t$$ has prototype -$codei% - const %Scalar% &%t% -%$$ -(see description of $cref/Scalar/Rosen34/Scalar/$$ below). - -$subhead x$$ -In all three cases, -the argument $icode x$$ has prototype -$codei% - const %Vector% &%x% -%$$ -and has size $icode n$$ -(see description of $cref/Vector/Rosen34/Vector/$$ below). - -$subhead f$$ -The argument $icode f$$ to $icode%F%.Ode%$$ has prototype -$codei% - %Vector% &%f% -%$$ -On input and output, $icode f$$ is a vector of size $icode n$$ -and the input values of the elements of $icode f$$ do not matter. -On output, -$icode f$$ is set equal to $latex F(t, x)$$ -(see $icode F(t, x)$$ in $cref/Description/Rosen34/Description/$$). - -$subhead f_t$$ -The argument $icode f_t$$ to $icode%F%.Ode_ind%$$ has prototype -$codei% - %Vector% &%f_t% -%$$ -On input and output, $icode f_t$$ is a vector of size $icode n$$ -and the input values of the elements of $icode f_t$$ do not matter. -On output, the $th i$$ element of -$icode f_t$$ is set equal to $latex \partial_t F_i (t, x)$$ -(see $icode F(t, x)$$ in $cref/Description/Rosen34/Description/$$). - -$subhead f_x$$ -The argument $icode f_x$$ to $icode%F%.Ode_dep%$$ has prototype -$codei% - %Vector% &%f_x% -%$$ -On input and output, $icode f_x$$ is a vector of size $icode%n%*%n%$$ -and the input values of the elements of $icode f_x$$ do not matter. -On output, the [$icode%i%*%n%+%j%$$] element of -$icode f_x$$ is set equal to $latex \partial_{x(j)} F_i (t, x)$$ -(see $icode F(t, x)$$ in $cref/Description/Rosen34/Description/$$). - -$subhead Nan$$ -If any of the elements of $icode f$$, $icode f_t$$, or $icode f_x$$ -have the value not a number $code nan$$, -the routine $code Rosen34$$ returns with all the -elements of $icode xf$$ and $icode e$$ equal to $code nan$$. - -$subhead Warning$$ -The arguments $icode f$$, $icode f_t$$, and $icode f_x$$ -must have a call by reference in their prototypes; i.e., -do not forget the $code &$$ in the prototype for -$icode f$$, $icode f_t$$ and $icode f_x$$. - -$subhead Optimization$$ -Every call of the form -$codei% - %F%.Ode_ind(%t%, %x%, %f_t%) -%$$ -is directly followed by a call of the form -$codei% - %F%.Ode_dep(%t%, %x%, %f_x%) -%$$ -where the arguments $icode t$$ and $icode x$$ have not changed between calls. -In many cases it is faster to compute the values of $icode f_t$$ -and $icode f_x$$ together and then pass them back one at a time. - -$head M$$ -The argument $icode M$$ has prototype -$codei% - size_t %M% -%$$ -It specifies the number of steps -to use when solving the differential equation. -This must be greater than or equal one. -The step size is given by $latex h = (tf - ti) / M$$, thus -the larger $icode M$$, the more accurate the -return value $icode xf$$ is as an approximation -for $latex X(tf)$$. - -$head ti$$ -The argument $icode ti$$ has prototype -$codei% - const %Scalar% &%ti% -%$$ -(see description of $cref/Scalar/Rosen34/Scalar/$$ below). -It specifies the initial time for $icode t$$ in the -differential equation; i.e., -the time corresponding to the value $icode xi$$. - -$head tf$$ -The argument $icode tf$$ has prototype -$codei% - const %Scalar% &%tf% -%$$ -It specifies the final time for $icode t$$ in the -differential equation; i.e., -the time corresponding to the value $icode xf$$. - -$head xi$$ -The argument $icode xi$$ has the prototype -$codei% - const %Vector% &%xi% -%$$ -and the size of $icode xi$$ is equal to $icode n$$. -It specifies the value of $latex X(ti)$$ - -$head e$$ -The argument $icode e$$ is optional and has the prototype -$codei% - %Vector% &%e% -%$$ -If $icode e$$ is present, -the size of $icode e$$ must be equal to $icode n$$. -The input value of the elements of $icode e$$ does not matter. -On output -it contains an element by element -estimated bound for the absolute value of the error in $icode xf$$ -$latex \[ - e = O( h^4 ) -\] $$ -where $latex h = (tf - ti) / M$$ is the step size. - -$head Scalar$$ -The type $icode Scalar$$ must satisfy the conditions -for a $cref NumericType$$ type. -The routine $cref CheckNumericType$$ will generate an error message -if this is not the case. -In addition, the following operations must be defined for -$icode Scalar$$ objects $icode a$$ and $icode b$$: - -$table -$bold Operation$$ $cnext $bold Description$$ $rnext -$icode%a% < %b%$$ $cnext - less than operator (returns a $code bool$$ object) -$tend - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type Scalar/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Parallel Mode$$ -For each set of types -$cref/Scalar/Rosen34/Scalar/$$, -$cref/Vector/Rosen34/Vector/$$, and -$cref/Fun/Rosen34/Fun/$$, -the first call to $code Rosen34$$ -must not be $cref/parallel/ta_in_parallel/$$ execution mode. - -$head Example$$ -$children% - example/rosen_34.cpp -%$$ -The file -$cref rosen_34.cpp$$ -contains an example and test a test of using this routine. -It returns true if it succeeds and false otherwise. - -$head Source Code$$ -The source code for this routine is in the file -$code cppad/rosen_34.hpp$$. - -$end --------------------------------------------------------------------------- -*/ - -# include -# include -# include -# include -# include -# include -# include - -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -namespace CppAD { // BEGIN CppAD namespace - -template -Vector Rosen34( - Fun &F , - size_t M , - const Scalar &ti , - const Scalar &tf , - const Vector &xi ) -{ Vector e( xi.size() ); - return Rosen34(F, M, ti, tf, xi, e); -} - -template -Vector Rosen34( - Fun &F , - size_t M , - const Scalar &ti , - const Scalar &tf , - const Vector &xi , - Vector &e ) -{ - CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - - // check numeric type specifications - CheckNumericType(); - - // check simple vector class specifications - CheckSimpleVector(); - - // Parameters for Shampine's Rosenbrock method - // are static to avoid recalculation on each call and - // do not use Vector to avoid possible memory leak - static Scalar a[3] = { - Scalar(0), - Scalar(1), - Scalar(3) / Scalar(5) - }; - static Scalar b[2 * 2] = { - Scalar(1), - Scalar(0), - Scalar(24) / Scalar(25), - Scalar(3) / Scalar(25) - }; - static Scalar ct[4] = { - Scalar(1) / Scalar(2), - - Scalar(3) / Scalar(2), - Scalar(121) / Scalar(50), - Scalar(29) / Scalar(250) - }; - static Scalar cg[3 * 3] = { - - Scalar(4), - Scalar(0), - Scalar(0), - Scalar(186) / Scalar(25), - Scalar(6) / Scalar(5), - Scalar(0), - - Scalar(56) / Scalar(125), - - Scalar(27) / Scalar(125), - - Scalar(1) / Scalar(5) - }; - static Scalar d3[3] = { - Scalar(97) / Scalar(108), - Scalar(11) / Scalar(72), - Scalar(25) / Scalar(216) - }; - static Scalar d4[4] = { - Scalar(19) / Scalar(18), - Scalar(1) / Scalar(4), - Scalar(25) / Scalar(216), - Scalar(125) / Scalar(216) - }; - CPPAD_ASSERT_KNOWN( - M >= 1, - "Error in Rosen34: the number of steps is less than one" - ); - CPPAD_ASSERT_KNOWN( - e.size() == xi.size(), - "Error in Rosen34: size of e not equal to size of xi" - ); - size_t i, j, k, l, m; // indices - - size_t n = xi.size(); // number of components in X(t) - Scalar ns = Scalar(double(M)); // number of steps as Scalar object - Scalar h = (tf - ti) / ns; // step size - Scalar zero = Scalar(0); // some constants - Scalar one = Scalar(1); - Scalar two = Scalar(2); - - // permutation vectors needed for LU factorization routine - CppAD::vector ip(n), jp(n); - - // vectors used to store values returned by F - Vector E(n * n), Eg(n), f_t(n); - Vector g(n * 3), x3(n), x4(n), xf(n), ftmp(n), xtmp(n), nan_vec(n); - - // initialize e = 0, nan_vec = nan - for(i = 0; i < n; i++) - { e[i] = zero; - nan_vec[i] = nan(zero); - } - - xf = xi; // initialize solution - for(m = 0; m < M; m++) - { // time at beginning of this interval - Scalar t = ti * (Scalar(int(M - m)) / ns) - + tf * (Scalar(int(m)) / ns); - - // value of x at beginning of this interval - x3 = x4 = xf; - - // evaluate partial derivatives at beginning of this interval - F.Ode_ind(t, xf, f_t); - F.Ode_dep(t, xf, E); // E = f_x - if( hasnan(f_t) || hasnan(E) ) - { e = nan_vec; - return nan_vec; - } - - // E = I - f_x * h / 2 - for(i = 0; i < n; i++) - { for(j = 0; j < n; j++) - E[i * n + j] = - E[i * n + j] * h / two; - E[i * n + i] += one; - } - - // LU factor the matrix E -# ifndef NDEBUG - int sign = LuFactor(ip, jp, E); -# else - LuFactor(ip, jp, E); -# endif - CPPAD_ASSERT_KNOWN( - sign != 0, - "Error in Rosen34: I - f_x * h / 2 not invertible" - ); - - // loop over integration steps - for(k = 0; k < 3; k++) - { // set location for next function evaluation - xtmp = xf; - for(l = 0; l < k; l++) - { // loop over previous function evaluations - Scalar bkl = b[(k-1)*2 + l]; - for(i = 0; i < n; i++) - { // loop over elements of x - xtmp[i] += bkl * g[i*3 + l] * h; - } - } - // ftmp = F(t + a[k] * h, xtmp) - F.Ode(t + a[k] * h, xtmp, ftmp); - if( hasnan(ftmp) ) - { e = nan_vec; - return nan_vec; - } - - // Form Eg for this integration step - for(i = 0; i < n; i++) - Eg[i] = ftmp[i] + ct[k] * f_t[i] * h; - for(l = 0; l < k; l++) - { for(i = 0; i < n; i++) - Eg[i] += cg[(k-1)*3 + l] * g[i*3 + l]; - } - - // Solve the equation E * g = Eg - LuInvert(ip, jp, E, Eg); - - // save solution and advance x3, x4 - for(i = 0; i < n; i++) - { g[i*3 + k] = Eg[i]; - x3[i] += h * d3[k] * Eg[i]; - x4[i] += h * d4[k] * Eg[i]; - } - } - // Form Eg for last update to x4 only - for(i = 0; i < n; i++) - Eg[i] = ftmp[i] + ct[3] * f_t[i] * h; - for(l = 0; l < 3; l++) - { for(i = 0; i < n; i++) - Eg[i] += cg[2*3 + l] * g[i*3 + l]; - } - - // Solve the equation E * g = Eg - LuInvert(ip, jp, E, Eg); - - // advance x4 and accumulate error bound - for(i = 0; i < n; i++) - { x4[i] += h * d4[3] * Eg[i]; - - // cant use abs because cppad.hpp may not be included - Scalar diff = x4[i] - x3[i]; - if( diff < zero ) - e[i] -= diff; - else e[i] += diff; - } - - // advance xf for this step using x4 - xf = x4; - } - return xf; -} - -} // End CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/runge_45.hpp b/ct_core/include/ct/external/cppad/utility/runge_45.hpp deleted file mode 100644 index 0bb29de55..000000000 --- a/ct_core/include/ct/external/cppad/utility/runge_45.hpp +++ /dev/null @@ -1,429 +0,0 @@ -// $Id: runge_45.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_RUNGE_45_HPP -# define CPPAD_RUNGE_45_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin Runge45$$ -$spell - std - fabs - cppad.hpp - bool - xf - templated - const - Runge-Kutta - CppAD - xi - ti - tf - Karp -$$ - - -$section An Embedded 4th and 5th Order Runge-Kutta ODE Solver$$ -$mindex Runge45 Runge Kutta solve differential equation$$ - -$head Syntax$$ -$codei%# include -%$$ -$icode%xf% = Runge45(%F%, %M%, %ti%, %tf%, %xi%) -%$$ -$icode%xf% = Runge45(%F%, %M%, %ti%, %tf%, %xi%, %e%) -%$$ - - -$head Purpose$$ -This is an implementation of the -Cash-Karp embedded 4th and 5th order Runge-Kutta ODE solver -described in Section 16.2 of $cref/Numerical Recipes/Bib/Numerical Recipes/$$. -We use $latex n$$ for the size of the vector $icode xi$$. -Let $latex \B{R}$$ denote the real numbers -and let $latex F : \B{R} \times \B{R}^n \rightarrow \B{R}^n$$ -be a smooth function. -The return value $icode xf$$ contains a 5th order -approximation for the value $latex X(tf)$$ where -$latex X : [ti , tf] \rightarrow \B{R}^n$$ is defined by -the following initial value problem: -$latex \[ -\begin{array}{rcl} - X(ti) & = & xi \\ - X'(t) & = & F[t , X(t)] -\end{array} -\] $$ -If your set of ordinary differential equations -are stiff, an implicit method may be better -(perhaps $cref Rosen34$$.) - -$head Operation Sequence$$ -The $cref/operation sequence/glossary/Operation/Sequence/$$ for $icode Runge$$ -does not depend on any of its $icode Scalar$$ input values provided that -the operation sequence for -$codei% - %F%.Ode(%t%, %x%, %f%) -%$$ -does not on any of its $icode Scalar$$ inputs (see below). - -$head Include$$ -The file $code cppad/runge_45.hpp$$ is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of -the $code CppAD$$ routines. - -$head xf$$ -The return value $icode xf$$ has the prototype -$codei% - %Vector% %xf% -%$$ -and the size of $icode xf$$ is equal to $icode n$$ -(see description of $cref/Vector/Runge45/Vector/$$ below). -$latex \[ - X(tf) = xf + O( h^6 ) -\] $$ -where $latex h = (tf - ti) / M$$ is the step size. -If $icode xf$$ contains not a number $cref nan$$, -see the discussion for $cref/f/Runge45/Fun/f/$$. - -$head Fun$$ -The class $icode Fun$$ -and the object $icode F$$ satisfy the prototype -$codei% - %Fun% &%F% -%$$ -The object $icode F$$ (and the class $icode Fun$$) -must have a member function named $code Ode$$ -that supports the syntax -$codei% - %F%.Ode(%t%, %x%, %f%) -%$$ - -$subhead t$$ -The argument $icode t$$ to $icode%F%.Ode%$$ has prototype -$codei% - const %Scalar% &%t% -%$$ -(see description of $cref/Scalar/Runge45/Scalar/$$ below). - -$subhead x$$ -The argument $icode x$$ to $icode%F%.Ode%$$ has prototype -$codei% - const %Vector% &%x% -%$$ -and has size $icode n$$ -(see description of $cref/Vector/Runge45/Vector/$$ below). - -$subhead f$$ -The argument $icode f$$ to $icode%F%.Ode%$$ has prototype -$codei% - %Vector% &%f% -%$$ -On input and output, $icode f$$ is a vector of size $icode n$$ -and the input values of the elements of $icode f$$ do not matter. -On output, -$icode f$$ is set equal to $latex F(t, x)$$ in the differential equation. -If any of the elements of $icode f$$ have the value not a number $code nan$$ -the routine $code Runge45$$ returns with all the -elements of $icode xf$$ and $icode e$$ equal to $code nan$$. - -$subhead Warning$$ -The argument $icode f$$ to $icode%F%.Ode%$$ -must have a call by reference in its prototype; i.e., -do not forget the $code &$$ in the prototype for $icode f$$. - -$head M$$ -The argument $icode M$$ has prototype -$codei% - size_t %M% -%$$ -It specifies the number of steps -to use when solving the differential equation. -This must be greater than or equal one. -The step size is given by $latex h = (tf - ti) / M$$, thus -the larger $icode M$$, the more accurate the -return value $icode xf$$ is as an approximation -for $latex X(tf)$$. - -$head ti$$ -The argument $icode ti$$ has prototype -$codei% - const %Scalar% &%ti% -%$$ -(see description of $cref/Scalar/Runge45/Scalar/$$ below). -It specifies the initial time for $icode t$$ in the -differential equation; i.e., -the time corresponding to the value $icode xi$$. - -$head tf$$ -The argument $icode tf$$ has prototype -$codei% - const %Scalar% &%tf% -%$$ -It specifies the final time for $icode t$$ in the -differential equation; i.e., -the time corresponding to the value $icode xf$$. - -$head xi$$ -The argument $icode xi$$ has the prototype -$codei% - const %Vector% &%xi% -%$$ -and the size of $icode xi$$ is equal to $icode n$$. -It specifies the value of $latex X(ti)$$ - -$head e$$ -The argument $icode e$$ is optional and has the prototype -$codei% - %Vector% &%e% -%$$ -If $icode e$$ is present, -the size of $icode e$$ must be equal to $icode n$$. -The input value of the elements of $icode e$$ does not matter. -On output -it contains an element by element -estimated bound for the absolute value of the error in $icode xf$$ -$latex \[ - e = O( h^5 ) -\] $$ -where $latex h = (tf - ti) / M$$ is the step size. -If on output, $icode e$$ contains not a number $code nan$$, -see the discussion for $cref/f/Runge45/Fun/f/$$. - -$head Scalar$$ -The type $icode Scalar$$ must satisfy the conditions -for a $cref NumericType$$ type. -The routine $cref CheckNumericType$$ will generate an error message -if this is not the case. - -$subhead fabs$$ -In addition, the following function must be defined for -$icode Scalar$$ objects $icode a$$ and $icode b$$ -$codei% - %a% = fabs(%b%) -%$$ -Note that this operation is only used for computing $icode e$$; hence -the operation sequence for $icode xf$$ can still be independent of -the arguments to $code Runge45$$ even if -$codei% - fabs(%b%) = std::max(-%b%, %b%) -%$$. - -$head Vector$$ -The type $icode Vector$$ must be a $cref SimpleVector$$ class with -$cref/elements of type Scalar/SimpleVector/Elements of Specified Type/$$. -The routine $cref CheckSimpleVector$$ will generate an error message -if this is not the case. - -$head Parallel Mode$$ -For each set of types -$cref/Scalar/Runge45/Scalar/$$, -$cref/Vector/Runge45/Vector/$$, and -$cref/Fun/Runge45/Fun/$$, -the first call to $code Runge45$$ -must not be $cref/parallel/ta_in_parallel/$$ execution mode. - - -$head Example$$ -$children% - example/runge45_1.cpp% - example/runge45_2.cpp -%$$ -The file -$cref runge45_1.cpp$$ -contains a simple example and test of $code Runge45$$. -It returns true if it succeeds and false otherwise. -$pre - -$$ -The file -$cref runge45_2.cpp$$ contains an example using $code Runge45$$ -in the context of algorithmic differentiation. -It also returns true if it succeeds and false otherwise. - -$head Source Code$$ -The source code for this routine is in the file -$code cppad/runge_45.hpp$$. - -$end --------------------------------------------------------------------------- -*/ -# include -# include -# include -# include -# include - -// needed before one can use CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL -# include - -namespace CppAD { // BEGIN CppAD namespace - -template -Vector Runge45( - Fun &F , - size_t M , - const Scalar &ti , - const Scalar &tf , - const Vector &xi ) -{ Vector e( xi.size() ); - return Runge45(F, M, ti, tf, xi, e); -} - -template -Vector Runge45( - Fun &F , - size_t M , - const Scalar &ti , - const Scalar &tf , - const Vector &xi , - Vector &e ) -{ - CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - - // check numeric type specifications - CheckNumericType(); - - // check simple vector class specifications - CheckSimpleVector(); - - // Cash-Karp parameters for embedded Runge-Kutta method - // are static to avoid recalculation on each call and - // do not use Vector to avoid possible memory leak - static Scalar a[6] = { - Scalar(0), - Scalar(1) / Scalar(5), - Scalar(3) / Scalar(10), - Scalar(3) / Scalar(5), - Scalar(1), - Scalar(7) / Scalar(8) - }; - static Scalar b[5 * 5] = { - Scalar(1) / Scalar(5), - Scalar(0), - Scalar(0), - Scalar(0), - Scalar(0), - - Scalar(3) / Scalar(40), - Scalar(9) / Scalar(40), - Scalar(0), - Scalar(0), - Scalar(0), - - Scalar(3) / Scalar(10), - -Scalar(9) / Scalar(10), - Scalar(6) / Scalar(5), - Scalar(0), - Scalar(0), - - -Scalar(11) / Scalar(54), - Scalar(5) / Scalar(2), - -Scalar(70) / Scalar(27), - Scalar(35) / Scalar(27), - Scalar(0), - - Scalar(1631) / Scalar(55296), - Scalar(175) / Scalar(512), - Scalar(575) / Scalar(13824), - Scalar(44275) / Scalar(110592), - Scalar(253) / Scalar(4096) - }; - static Scalar c4[6] = { - Scalar(2825) / Scalar(27648), - Scalar(0), - Scalar(18575) / Scalar(48384), - Scalar(13525) / Scalar(55296), - Scalar(277) / Scalar(14336), - Scalar(1) / Scalar(4), - }; - static Scalar c5[6] = { - Scalar(37) / Scalar(378), - Scalar(0), - Scalar(250) / Scalar(621), - Scalar(125) / Scalar(594), - Scalar(0), - Scalar(512) / Scalar(1771) - }; - - CPPAD_ASSERT_KNOWN( - M >= 1, - "Error in Runge45: the number of steps is less than one" - ); - CPPAD_ASSERT_KNOWN( - e.size() == xi.size(), - "Error in Runge45: size of e not equal to size of xi" - ); - size_t i, j, k, m; // indices - - size_t n = xi.size(); // number of components in X(t) - Scalar ns = Scalar(int(M)); // number of steps as Scalar object - Scalar h = (tf - ti) / ns; // step size - Scalar zero_or_nan = Scalar(0); // zero (nan if Ode returns has a nan) - for(i = 0; i < n; i++) // initialize e = 0 - e[i] = zero_or_nan; - - // vectors used to store values returned by F - Vector fh(6 * n), xtmp(n), ftmp(n), x4(n), x5(n), xf(n); - - xf = xi; // initialize solution - for(m = 0; m < M; m++) - { // time at beginning of this interval - // (convert to int to avoid MS compiler warning) - Scalar t = ti * (Scalar(int(M - m)) / ns) - + tf * (Scalar(int(m)) / ns); - - // loop over integration steps - x4 = x5 = xf; // start x4 and x5 at same point for each step - for(j = 0; j < 6; j++) - { // loop over function evaluations for this step - xtmp = xf; // location for next function evaluation - for(k = 0; k < j; k++) - { // loop over previous function evaluations - Scalar bjk = b[ (j-1) * 5 + k ]; - for(i = 0; i < n; i++) - { // loop over elements of x - xtmp[i] += bjk * fh[i * 6 + k]; - } - } - // ftmp = F(t + a[j] * h, xtmp) - F.Ode(t + a[j] * h, xtmp, ftmp); - - // if ftmp has a nan, set zero_or_nan to nan - for(i = 0; i < n; i++) - zero_or_nan *= ftmp[i]; - - for(i = 0; i < n; i++) - { // loop over elements of x - Scalar fhi = ftmp[i] * h; - fh[i * 6 + j] = fhi; - x4[i] += c4[j] * fhi; - x5[i] += c5[j] * fhi; - x5[i] += zero_or_nan; - } - } - // accumulate error bound - for(i = 0; i < n; i++) - { // cant use abs because cppad.hpp may not be included - Scalar diff = x5[i] - x4[i]; - e[i] += fabs(diff); - e[i] += zero_or_nan; - } - - // advance xf for this step using x5 - xf = x5; - } - return xf; -} - -} // End CppAD namespace - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/set_union.hpp b/ct_core/include/ct/external/cppad/utility/set_union.hpp deleted file mode 100644 index 2b6767e52..000000000 --- a/ct_core/include/ct/external/cppad/utility/set_union.hpp +++ /dev/null @@ -1,89 +0,0 @@ -// $Id$ -# ifndef CPPAD_UTILITY_SET_UNION_HPP -# define CPPAD_UTILITY_SET_UNION_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-16 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin set_union$$ -$spell - set - const - std -$$ - -$section Union of Standard Sets$$ - -$head Syntax$$ -$icode%result% = set_union(%left%, %right%)%$$ - -$head Purpose$$ -This is a simplified (and restricted) interface to -the $code std::union$$ operation. - -$head Element$$ -This is the type of the elements of the sets. - -$head left$$ -This argument has prototype -$codei% - const std::set<%Element%>& %left% -%$$ - -$head right$$ -This argument has prototype -$codei% - const std::set<%Element%>& %right% -%$$ - -$head result$$ -The return value has prototype -$codei% - std::set<%Element%>& %result% -%$$ -It contains the union of $icode left$$ and $icode right$$. -Note that C++11 detects that the return value is a temporary -and uses it for the result instead of making a separate copy. - -$children% - example/set_union.cpp -%$$ -$head Example$$ -The file $cref set_union.cpp$$ contains an example and test of this -operation. It returns true if the test passes and false otherwise. - - -$end -*/ - -# include -# include -# include - -namespace CppAD { - template - std::set set_union( - const std::set& left , - const std::set& right ) - { std::set result; - std::set_union( - left.begin() , - left.end() , - right.begin() , - right.end() , - std::inserter(result, result.begin()) - ); - return result; - } -} - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/speed_test.hpp b/ct_core/include/ct/external/cppad/utility/speed_test.hpp deleted file mode 100644 index 13d4c16f6..000000000 --- a/ct_core/include/ct/external/cppad/utility/speed_test.hpp +++ /dev/null @@ -1,470 +0,0 @@ -// $Id: speed_test.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_SPEED_TEST_HPP -# define CPPAD_SPEED_TEST_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin speed_test$$ -$spell - gettimeofday - vec - cppad.hpp - Microsoft - namespace - std - const - cout - ctime - ifdef - const - endif - cpp -$$ - - -$section Run One Speed Test and Return Results$$ -$mindex speed_test$$ - -$head Syntax$$ -$codei%# include -%$$ -$icode%rate_vec% = speed_test(%test%, %size_vec%, %time_min%)%$$ - -$head Purpose$$ -The $code speed_test$$ function executes a speed test -for various sized problems -and reports the rate of execution. - -$head Motivation$$ -It is important to separate small calculation units -and test them individually. -This way individual changes can be tested in the context of the -routine that they are in. -On many machines, accurate timing of a very short execution -sequences is not possible. -In addition, -there may be set up and tear down time for a test that -we do not really want included in the timing. -For this reason $code speed_test$$ -automatically determines how many times to -repeat the section of the test that we wish to time. - - -$head Include$$ -The file $code cppad/speed_test.hpp$$ defines the -$code speed_test$$ function. -This file is included by $code cppad/cppad.hpp$$ -and it can also be included separately with out the rest of -the $code CppAD$$ routines. - -$head Vector$$ -We use $icode Vector$$ to denote a -$cref/simple vector class/SimpleVector/$$ with elements -of type $code size_t$$. - -$head test$$ -The $code speed_test$$ argument $icode test$$ is a function with the syntax -$codei% - %test%(%size%, %repeat%) -%$$ -and its return value is $code void$$. - -$subhead size$$ -The $icode test$$ argument $icode size$$ has prototype -$codei% - size_t %size% -%$$ -It specifies the size for this test. - -$subhead repeat$$ -The $icode test$$ argument $icode repeat$$ has prototype -$codei% - size_t %repeat% -%$$ -It specifies the number of times to repeat the test. - -$head size_vec$$ -The $code speed_test$$ argument $icode size_vec$$ has prototype -$codei% - const %Vector%& %size_vec% -%$$ -This vector determines the size for each of the tests problems. - -$head time_min$$ -The argument $icode time_min$$ has prototype -$codei% - double %time_min% -%$$ -It specifies the minimum amount of time in seconds -that the $icode test$$ routine should take. -The $icode repeat$$ argument to $icode test$$ is increased -until this amount of execution time is reached. - -$head rate_vec$$ -The return value $icode rate_vec$$ has prototype -$codei% - %Vector%& %rate_vec% -%$$ -We use $latex n$$ to denote its size which is the same as -the vector $icode size_vec$$. -For $latex i = 0 , \ldots , n-1$$, -$codei% - %rate_vec%[%i%] -%$$ -is the ratio of $icode repeat$$ divided by time in seconds -for the problem with size $icode%size_vec%[%i%]%$$. - -$head Timing$$ -If your system supports the unix $code gettimeofday$$ function, -it will be used to measure time. -Otherwise, -time is measured by the difference in -$codep - (double) clock() / (double) CLOCKS_PER_SEC -$$ -in the context of the standard $code $$ definitions. - -$children% - speed/example/speed_test.cpp -%$$ -$head Example$$ -The routine $cref speed_test.cpp$$ is an example and test -of $code speed_test$$. - -$end ------------------------------------------------------------------------ -*/ - -# include -# include - -# include -# include - - -namespace CppAD { // BEGIN CppAD namespace - -// implemented as an inline so that can include in multiple link modules -// with this same file -template -inline Vector speed_test( - void test(size_t size, size_t repeat), - const Vector& size_vec , - double time_min ) -{ - // check that size_vec is a simple vector with size_t elements - CheckSimpleVector(); - - size_t n = size_vec.size(); - Vector rate_vec(n); - size_t i; - for(i = 0; i < n; i++) - { size_t size = size_vec[i]; - size_t repeat = 1; - double s0 = elapsed_seconds(); - double s1 = elapsed_seconds(); - while( s1 - s0 < time_min ) - { repeat = 2 * repeat; - s0 = elapsed_seconds(); - test(size, repeat); - s1 = elapsed_seconds(); - } - rate_vec[i] = (size_t)(.5 + repeat / (s1 - s0)); - } - return rate_vec; -} - -} // END CppAD namespace - -/* -$begin SpeedTest$$ -$spell - cppad.hpp - Microsoft - namespace - std - const - cout - ctime - ifdef - const - endif - cpp -$$ - - -$section Run One Speed Test and Print Results$$ -$mindex SpeedTest$$ - -$head Syntax$$ - -$codei%# include -%$$ -$codei%SpeedTest(%Test%, %first%, %inc%, %last%)%$$ - - -$head Purpose$$ -The $code SpeedTest$$ function executes a speed test -for various sized problems -and reports the results on standard output; i.e. $code std::cout$$. -The size of each test problem is included in its report -(unless $icode first$$ is equal to $icode last$$). - -$head Motivation$$ -It is important to separate small calculation units -and test them individually. -This way individual changes can be tested in the context of the -routine that they are in. -On many machines, accurate timing of a very short execution -sequences is not possible. -In addition, -there may be set up time for a test that -we do not really want included in the timing. -For this reason $code SpeedTest$$ -automatically determines how many times to -repeat the section of the test that we wish to time. - - -$head Include$$ -The file $code speed_test.hpp$$ contains the -$code SpeedTest$$ function. -This file is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of -the $code CppAD$$ routines. - -$head Test$$ -The $code SpeedTest$$ argument $icode Test$$ is a function with the syntax -$codei% - %name% = %Test%(%size%, %repeat%) -%$$ - -$subhead size$$ -The $icode Test$$ argument $icode size$$ has prototype -$codei% - size_t %size% -%$$ -It specifies the size for this test. - -$subhead repeat$$ -The $icode Test$$ argument $icode repeat$$ has prototype -$codei% - size_t %repeat% -%$$ -It specifies the number of times to repeat the test. - -$subhead name$$ -The $icode Test$$ result $icode name$$ has prototype -$codei% - std::string %name% -%$$ -The results for this test are reported on $code std::cout$$ -with $icode name$$ as an identifier for the test. -It is assumed that, -for the duration of this call to $code SpeedTest$$, -$icode Test$$ will always return -the same value for $icode name$$. -If $icode name$$ is the empty string, -no test name is reported by $code SpeedTest$$. - -$head first$$ -The $code SpeedTest$$ argument $icode first$$ has prototype -$codei% - size_t %first% -%$$ -It specifies the size of the first test problem reported by this call to -$code SpeedTest$$. - -$head last$$ -The $code SpeedTest$$ argument $icode last$$ has prototype -$codei% - size_t %last% -%$$ -It specifies the size of the last test problem reported by this call to -$code SpeedTest$$. - -$head inc$$ -The $code SpeedTest$$ argument $icode inc$$ has prototype -$codei% - int %inc% -%$$ -It specifies the increment between problem sizes; i.e., -all values of $icode size$$ in calls to $icode Test$$ are given by -$codei% - %size% = %first% + %j% * %inc% -%$$ -where $icode j$$ is a positive integer. -The increment can be positive or negative but it cannot be zero. -The values $icode first$$, $icode last$$ and $icode inc$$ must -satisfy the relation -$latex \[ - inc * ( last - first ) \geq 0 -\] $$ - -$head rate$$ -The value displayed in the $code rate$$ column on $code std::cout$$ -is defined as the value of $icode repeat$$ divided by the -corresponding elapsed execution time in seconds. -The elapsed execution time is measured by the difference in -$codep - (double) clock() / (double) CLOCKS_PER_SEC -$$ -in the context of the standard $code $$ definitions. - - -$head Errors$$ -If one of the restrictions above is violated, -the CppAD error handler is used to report the error. -You can redefine this action using the instructions in -$cref ErrorHandler$$ - -$head Example$$ -$children% - speed/example/speed_program.cpp -%$$ -The program $cref speed_program.cpp$$ is an example usage -of $code SpeedTest$$. - -$end ------------------------------------------------------------------------ -*/ -// BEGIN C++ - - -# include -# include -# include -# include - -namespace CppAD { // BEGIN CppAD namespace - -inline void SpeedTestNdigit(size_t value, size_t &ndigit, size_t &pow10) -{ pow10 = 10; - ndigit = 1; - while( pow10 <= value ) - { pow10 *= 10; - ndigit += 1; - } -} - -// implemented as an inline so that can include in multiple link modules -// with this same file -inline void SpeedTest( - std::string Test(size_t size, size_t repeat), - size_t first, - int inc, - size_t last -) -{ - - using std::cout; - using std::endl; - - size_t size; - size_t repeat; - size_t rate; - size_t digit; - size_t ndigit; - size_t pow10; - size_t maxSize; - size_t maxSizeDigit; - - double s0; - double s1; - - std::string name; - - CPPAD_ASSERT_KNOWN( - inc != 0 && first != 0 && last != 0, - "inc, first, or last is zero in call to SpeedTest" - ); - CPPAD_ASSERT_KNOWN( - (inc > 0 && first <= last) || (inc < 0 && first >= last), - "SpeedTest: increment is positive and first > last or " - "increment is negative and first < last" - ); - - // compute maxSize - maxSize = size = first; - while( (inc > 0 && size <= last) || (inc < 0 && size >= last) ) - { - if( size > maxSize ) - maxSize = size; - - // next size - if( ((int) size) + inc > 0 ) - size += inc; - else size = 0; - } - SpeedTestNdigit(maxSize, maxSizeDigit, pow10); - - size = first; - while( (inc > 0 && size <= last) || (inc < 0 && size >= last) ) - { - repeat = 1; - s0 = elapsed_seconds(); - s1 = elapsed_seconds(); - while( s1 - s0 < 1. ) - { repeat = 2 * repeat; - s0 = elapsed_seconds(); - name = Test(size, repeat); - s1 = elapsed_seconds(); - } - rate = (size_t)(.5 + repeat / (s1 - s0)); - - - if( size == first && name != "" ) - cout << name << endl; - - if( first != last ) - { - // convert int(size_t) to avoid warning on _MSC_VER sys - std::cout << "size = " << int(size); - - SpeedTestNdigit(size, ndigit, pow10); - while( ndigit < maxSizeDigit ) - { cout << " "; - ndigit++; - } - cout << " "; - } - - cout << "rate = "; - SpeedTestNdigit(rate, ndigit, pow10); - while( ndigit > 0 ) - { - pow10 /= 10; - digit = rate / pow10; - - // convert int(size_t) to avoid warning on _MSC_VER sys - std::cout << int(digit); - - rate = rate % pow10; - ndigit -= 1; - - if( (ndigit > 0) && (ndigit % 3 == 0) ) - cout << ","; - } - cout << endl; - - // next size - if( ((int) size) + inc > 0 ) - size += inc; - else size = 0; - } - return; -} - -} // END CppAD namespace - -// END C++ -# endif diff --git a/ct_core/include/ct/external/cppad/utility/thread_alloc.hpp b/ct_core/include/ct/external/cppad/utility/thread_alloc.hpp deleted file mode 100644 index 86ef0310d..000000000 --- a/ct_core/include/ct/external/cppad/utility/thread_alloc.hpp +++ /dev/null @@ -1,1515 +0,0 @@ -// $Id: thread_alloc.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_THREAD_ALLOC_HPP -# define CPPAD_THREAD_ALLOC_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -# include -# include -# include - - -# ifdef _MSC_VER -// Supress warning that Microsoft compiler changed its behavior and is now -// doing the correct thing at the statement: -// new(array + i) Type(); -# pragma warning(disable:4345) -# endif - -# include -# include -# include -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file thread_alloc.hpp -File used to define the CppAD multi-threading allocator class -*/ - -/*! -\def CPPAD_MAX_NUM_CAPACITY -Maximum number of different capacities the allocator will attempt. -This must be larger than the log base two of numeric_limit::max(). -*/ -# define CPPAD_MAX_NUM_CAPACITY 100 - -/*! -\def CPPAD_MIN_DOUBLE_CAPACITY -Minimum number of double values that will fit in an allocation. -*/ -# define CPPAD_MIN_DOUBLE_CAPACITY 16 - -/*! -\def CPPAD_TRACE_CAPACITY -If NDEBUG is not defined, print all calls to \c get_memory and \c return_memory -that correspond to this capacity and thread CPPAD_TRACE_THREAD. -(Note that if CPPAD_TRACE_CAPACITY is zero, or any other value not in the list -of capacities, no tracing will be done.) -*/ -# define CPPAD_TRACE_CAPACITY 0 - -/*! -\def CPPAD_TRACE_THREAD -If NDEBUG is not defined, print all calls to \c get_memory and \c return_memory -that correspond to this thead and capacity CPPAD_TRACE_CAPACITY. -*/ -# define CPPAD_TRACE_THREAD 0 - -/* -Note that Section 3.6.2 of ISO/IEC 14882:1998(E) states: "The storage for -objects with static storage duration (3.7.1) shall be zero-initialized -(8.5) before any other initialization takes place." -*/ - -/*! -Capacity vector for memory allocation block sizes. - -Only one of these objects should be created and used as a -static variable inside of the \c thread_alloc::capacity_info function. -*/ - -/*! -Allocator class that works well with an multi-threading environment. -*/ -class thread_alloc{ -// ============================================================================ -private: - - class capacity_t { - public: - /// number of capacity values actually used - size_t number; - /// the different capacity values - size_t value[CPPAD_MAX_NUM_CAPACITY]; - /// ctor - capacity_t(void) - { // Cannot figure out how to call thread_alloc::in_parallel here. - // CPPAD_ASSERT_UNKNOWN( - // ! thread_alloc::in_parallel() , "thread_alloc: " - // "parallel mode and parallel_setup not yet called." - // ); - number = 0; - size_t capacity = CPPAD_MIN_DOUBLE_CAPACITY * sizeof(double); - while( capacity < std::numeric_limits::max() / 2 ) - { CPPAD_ASSERT_UNKNOWN( number < CPPAD_MAX_NUM_CAPACITY ); - value[number++] = capacity; - // next capactiy is 3/2 times the current one - capacity = 3 * ( (capacity + 1) / 2 ); - } - CPPAD_ASSERT_UNKNOWN( number > 0 ); - } - }; - - class block_t { - public: - /// extra information (currently used by create and delete array) - size_t extra_; - /// an index that uniquely idenfifies both thread and capacity - size_t tc_index_; - /// pointer to the next memory allocation with the same tc_index_ - void* next_; - // ----------------------------------------------------------------- - /// make default constructor private. It is only used by constructor - /// for `root arrays below. - block_t(void) : extra_(0), tc_index_(0), next_(CPPAD_NULL) - { } - }; - - // --------------------------------------------------------------------- - /// Vector of fixed capacity values for this allocator - static const capacity_t* capacity_info(void) - { CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - static const capacity_t capacity; - return &capacity; - } - // --------------------------------------------------------------------- - /// Structure of information for each thread - struct thread_alloc_info { - /// count of available bytes for this thread - size_t count_inuse_; - /// count of inuse bytes for this thread - size_t count_available_; - /// root of available list for this thread and each capacity - block_t root_available_[CPPAD_MAX_NUM_CAPACITY]; - /// root of inuse list for this thread and each capacity - /// If NDEBUG is true, this memory is not used, but it still - /// helps separate this structure from one for the next thread. - block_t root_inuse_[CPPAD_MAX_NUM_CAPACITY]; - }; - // --------------------------------------------------------------------- - /*! - Set and Get hold available memory flag. - - \param set [in] - if true, the value returned by this return is changed. - - \param new_value [in] - if \a set is true, this is the new value returned by this routine. - Otherwise, \c new_value is ignored. - - \return - the current setting for this routine (which is initially false). - */ - static bool set_get_hold_memory(bool set, bool new_value = false) - { static bool value = false; - if( set ) - value = new_value; - return value; - } - // --------------------------------------------------------------------- - /*! - Get pointer to the information for this thread. - - \param thread [in] - Is the thread number for this information pointer. - - \param clear - If \a clear is true, then the information pointer for this thread - is deleted and the \c CPPAD_NULL pointer is returned. - There must be no memory currently in either the inuse or avaialble - lists when this routine is called. - - \return - is the current informaiton pointer for this thread. - If \a clear is false, and the current pointer is CPPAD_NULL, - a new infromation record is allocated and its pointer returned. - In this case, if \c info is the retured pointer, - info->count_inuse == 0 and - info->count_available == 0. - In addition, - for c = 0 , ... , CPPAD_MAX_NUM_CAPACITY-1 - info->root_inuse_[c].next_ == CPPAD_NULL and - info->root_available_[c].next_ == CPPAD_NULL. - */ - static thread_alloc_info* thread_info( - size_t thread , - bool clear = false ) - { static thread_alloc_info* all_info[CPPAD_MAX_NUM_THREADS]; - static thread_alloc_info zero_info; - - CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - - CPPAD_ASSERT_UNKNOWN( thread < CPPAD_MAX_NUM_THREADS ); - - thread_alloc_info* info = all_info[thread]; - if( clear ) - { if( info != CPPAD_NULL ) - { -# ifndef NDEBUG - CPPAD_ASSERT_UNKNOWN( - info->count_inuse_ == 0 && - info->count_available_ == 0 - ); - for(size_t c = 0; c < CPPAD_MAX_NUM_CAPACITY; c++) - { CPPAD_ASSERT_UNKNOWN( - info->root_inuse_[c].next_ == CPPAD_NULL && - info->root_available_[c].next_ == CPPAD_NULL - ); - } -# endif - if( thread != 0 ) - ::operator delete( reinterpret_cast(info) ); - info = CPPAD_NULL; - all_info[thread] = info; - } - } - else if( info == CPPAD_NULL ) - { if( thread == 0 ) - info = &zero_info; - else - { size_t size = sizeof(thread_alloc_info); - void* v_ptr = ::operator new(size); - info = reinterpret_cast(v_ptr); - } - all_info[thread] = info; - - // initialize the information record - for(size_t c = 0; c < CPPAD_MAX_NUM_CAPACITY; c++) - { info->root_inuse_[c].next_ = CPPAD_NULL; - info->root_available_[c].next_ = CPPAD_NULL; - } - info->count_inuse_ = 0; - info->count_available_ = 0; - } - return info; - } - // ----------------------------------------------------------------------- - /*! - Increase the number of bytes of memory that are currently in use; i.e., - that been obtained with \c get_memory and not yet returned. - - \param inc [in] - amount to increase memory in use. - - \param thread [in] - Thread for which we are increasing the number of bytes in use - (must be less than \c num_threads). - Durring parallel execution, this must be the thread - that is currently executing. - */ - static void inc_inuse(size_t inc, size_t thread) - { - CPPAD_ASSERT_UNKNOWN( thread < num_threads() ); - CPPAD_ASSERT_UNKNOWN( - thread == thread_num() || (! in_parallel()) - ); - thread_alloc_info* info = thread_info(thread); - - // do the addition - size_t result = info->count_inuse_ + inc; - CPPAD_ASSERT_UNKNOWN( result >= info->count_inuse_ ); - - info->count_inuse_ = result; - } - // ----------------------------------------------------------------------- - /*! - Increase the number of bytes of memory that are currently avaialble; i.e., - have been obtained obtained from the system and are being held future use. - - \copydetails inc_inuse - */ - static void inc_available(size_t inc, size_t thread) - { - CPPAD_ASSERT_UNKNOWN( thread < CPPAD_MAX_NUM_THREADS); - CPPAD_ASSERT_UNKNOWN( - thread == thread_num() || (! in_parallel()) - ); - thread_alloc_info* info = thread_info(thread); - // do the addition - size_t result = info->count_available_ + inc; - CPPAD_ASSERT_UNKNOWN( result >= info->count_available_ ); - - info->count_available_ = result; - } - // ----------------------------------------------------------------------- - /*! - Decrease the number of bytes of memory that are currently in use; i.e., - that been obtained with \c get_memory and not yet returned. - - \param dec [in] - amount to decrease number of bytes in use. - - \param thread [in] - Thread for which we are decreasing the number of bytes in use - (must be less than \c num_threads). - Durring parallel execution, this must be the thread - that is currently executing. - */ - static void dec_inuse(size_t dec, size_t thread) - { - CPPAD_ASSERT_UNKNOWN( - thread < num_threads() || (! in_parallel()) - ); - CPPAD_ASSERT_UNKNOWN( - thread == thread_num() || (! in_parallel()) - ); - thread_alloc_info* info = thread_info(thread); - - // do the subtraction - CPPAD_ASSERT_UNKNOWN( info->count_inuse_ >= dec ); - info->count_inuse_ = info->count_inuse_ - dec; - } - // ----------------------------------------------------------------------- - /*! - Decrease the number of bytes of memory that are currently avaialble; i.e., - have been obtained obtained from the system and are being held future use. - - \copydetails dec_inuse - */ - static void dec_available(size_t dec, size_t thread) - { - CPPAD_ASSERT_UNKNOWN( thread < CPPAD_MAX_NUM_THREADS); - CPPAD_ASSERT_UNKNOWN( - thread == thread_num() || (! in_parallel()) - ); - thread_alloc_info* info = thread_info(thread); - // do the subtraction - CPPAD_ASSERT_UNKNOWN( info->count_available_ >= dec ); - info->count_available_ = info->count_available_ - dec; - } - - // ---------------------------------------------------------------------- - /*! - Set and get the number of threads that are sharing memory. - - \param number_new - If \c number is zero, we are only retreiving the current maximum - number of threads. Otherwise, we are setting and retreiving - maximum number of threads. - - \return - the number of threads that are sharing memory. - If \c number_new is non-zero, the return value is equal to - \c number_new. - */ - static size_t set_get_num_threads(size_t number_new) - { static size_t number_user = 1; - - CPPAD_ASSERT_UNKNOWN( number_new <= CPPAD_MAX_NUM_THREADS ); - CPPAD_ASSERT_UNKNOWN( ! in_parallel() || (number_new == 0) ); - - // case where we are changing the number of threads - if( number_new != 0 ) - number_user = number_new; - - return number_user; - } - /*! - Set and call the routine that determine the current thread number. - - \return - returns value for the most recent setting for \a thread_num_new. - If \a set is true, - or the most recent setting is \c CPPAD_NULL (its initial value), - the return value is zero. - Otherwise the routine corresponding to the most recent setting - is called and its value returned by \c set_get_thread_num. - - \param thread_num_new [in] - If \a set is false, \a thread_num_new it is not used. - Otherwise, the current value of \c thread_num_new becomes the - most recent setting for thread_num. - - \param set - If \a set is true, then \a thread_num_new is becomes the most - recent setting for this \c set_get_thread_num. - */ - static size_t set_get_thread_num( - size_t (*thread_num_new)(void) , - bool set = false ) - { static size_t (*thread_num_user)(void) = CPPAD_NULL; - - if( set ) - { thread_num_user = thread_num_new; - return 0; - } - - if( thread_num_user == CPPAD_NULL ) - return 0; - - size_t thread = thread_num_user(); - CPPAD_ASSERT_KNOWN( - thread < set_get_num_threads(0) , - "parallel_setup: thread_num() >= num_threads" - ); - return thread; - } -// ============================================================================ -public: -/* -$begin ta_parallel_setup$$ -$spell - alloc - num - bool -$$ -$section Setup thread_alloc For Use in Multi-Threading Environment$$ -$mindex parallel initialize$$ - - - - -$head Syntax$$ -$codei%thread_alloc::parallel_setup(%num_threads%, %in_parallel%, %thread_num%) -%$$ - -$head Purpose$$ -By default there is only one thread and all execution is in sequential mode, -i.e., multiple threads are not sharing the same memory; i.e. -not in parallel mode. - -$head Speed$$ -It should be faster, even when $icode num_thread$$ is equal to one, -for $code thread_alloc$$ to hold onto memory. -This can be accomplished using the function call -$codei% - thread_alloc::hold_memory(true) -%$$ -see $cref/hold_memory/ta_hold_memory/$$. - -$head num_threads$$ -This argument has prototype -$codei% - size_t %num_threads% -%$$ -and must be greater than zero. -It specifies the number of threads that are sharing memory. -The case $icode%num_threads% == 1%$$ is a special case that is -used to terminate a multi-threading environment. - -$head in_parallel$$ -This function has prototype -$codei% - bool %in_parallel%(void) -%$$ -It must return $code true$$ if there is more than one thread -currently executing. -Otherwise it can return false. -$pre - -$$ -In the special case where $icode%num_threads% == 1%$$, -the routine $icode in_parallel$$ is not used. - -$head thread_num$$ -This function has prototype -$codei% - size_t %thread_num%(void) -%$$ -It must return a thread number that uniquely identifies the -currently executing thread. -Furthermore -$codei% - 0 <= %thread_num%() < %num_threads% -%$$. -In the special case where $icode%num_threads% == 1%$$, -the routine $icode thread_num$$ is not used. -$pre - -$$ -Note that this function is called by other routines so, -as soon as a new thread is executing, -one must be certain that $icode thread_num()$$ will -work for that thread. - -$head Restrictions$$ -The function $code parallel_setup$$ must be called before -the program enters $cref/parallel/ta_in_parallel/$$ execution mode. -In addition, this function cannot be called while in parallel mode. - -$head Example$$ -The files -$cref simple_ad_openmp.cpp$$, -$cref simple_ad_bthread.cpp$$, and -$cref simple_ad_pthread.cpp$$, -contain examples and tests that use this function. - -$end -*/ - /*! - Set thread_alloc up for parallel mode usage. - - \param num_threads [in] - Is the number of thread that may be executing at the same time. - - \param in_parallel [in] - Is the routine that determines if we are in parallel mode or not. - - \param thread_num [in] - Is the routine that determines the current thread number - (between zero and num_threads minus one). - */ - static void parallel_setup( - size_t num_threads , - bool (*in_parallel)(void) , - size_t (*thread_num)(void) ) - { - // Special case where we go back to single thread mode right away - // (previous settings may no longer be valid) - if( num_threads == 1 ) - { bool set = true; - set_get_num_threads(num_threads); - // emphasize that this routine is outside thread_alloc class - CppAD::set_get_in_parallel(CPPAD_NULL, set); - set_get_thread_num(CPPAD_NULL, set); - return; - } - - CPPAD_ASSERT_KNOWN( - num_threads <= CPPAD_MAX_NUM_THREADS , - "parallel_setup: num_threads is too large" - ); - CPPAD_ASSERT_KNOWN( - num_threads != 0 , - "parallel_setup: num_threads == zero" - ); - CPPAD_ASSERT_KNOWN( - in_parallel != CPPAD_NULL , - "parallel_setup: num_threads != 1 and in_parallel == CPPAD_NULL" - ); - CPPAD_ASSERT_KNOWN( - thread_num != CPPAD_NULL , - "parallel_setup: num_threads != 1 and thread_num == CPPAD_NULL" - ); - - // Make sure that constructors for all static variables in this file - // are called in sequential mode. - for(size_t thread = 0; thread < num_threads; thread++) - thread_info(thread); - capacity_info(); - size_t cap_bytes; - void* v_ptr = get_memory(0, cap_bytes); - - // free memory allocated by call to get_memory above - return_memory(v_ptr); - free_available( set_get_thread_num(CPPAD_NULL) ); - - // delay this so thread_num() call above is in previous mode - // (current setings may not yet be valid) - if( num_threads > 1 ) - { bool set = true; - set_get_num_threads(num_threads); - // emphasize that this routine is outside thread_alloc class - CppAD::set_get_in_parallel(in_parallel, set); - set_get_thread_num(thread_num, set); - } - } -/* -$begin ta_num_threads$$ -$spell - inv - CppAD - num - alloc -$$ -$section Get Number of Threads$$ - - -$head Syntax$$ -$icode%number% = thread_alloc::num_threads()%$$ - -$head Purpose$$ -Determine the number of threads as set during $cref/parallel_setup/ta_parallel_setup/$$. - -$head number$$ -The return value $icode number$$ has prototype -$codei% - size_t %number% -%$$ -and is equal to the value of -$cref/num_threads/ta_parallel_setup/num_threads/$$ -in the previous call to $icode parallel_setup$$. -If there was no such previous call, the value one is returned. - -$head Example$$ -The example and test $cref thread_alloc.cpp$$ uses this routine. - -$end -*/ - /*! - Get the current number of threads that thread_alloc can use. - */ - static size_t num_threads(void) - { return set_get_num_threads(0); } -/* ----------------------------------------------------------------------- -$begin ta_in_parallel$$ - -$section Is The Current Execution in Parallel Mode$$ -$mindex sequential$$ -$spell - thread_alloc - bool -$$ - - -$head Syntax$$ -$icode%flag% = thread_alloc::in_parallel()%$$ - -$head Purpose$$ -Some of the $cref thread_alloc$$ allocation routines have different -specifications for parallel (not sequential) execution mode. -This routine enables you to determine if the current execution mode -is sequential or parallel. - -$head flag$$ -The return value has prototype -$codei% - bool %flag% -%$$ -It is true if the current execution is in parallel mode -(possibly multi-threaded) and false otherwise (sequential mode). - -$head Example$$ -$cref thread_alloc.cpp$$ - -$end -*/ - /// Are we in a parallel execution state; i.e., is it possible that - /// other threads are currently executing. - static bool in_parallel(void) - { // emphasize that this routine is outside thread_alloc class - return CppAD::set_get_in_parallel(0); - } -/* ----------------------------------------------------------------------- -$begin ta_thread_num$$ -$spell - CppAD - num - thread_alloc - cppad.hpp -$$ - -$section Get the Current Thread Number$$ - - -$head Syntax$$ -$icode%thread% = thread_alloc::thread_num()%$$ - -$head Purpose$$ -Some of the $cref thread_alloc$$ allocation routines have a thread number. -This routine enables you to determine the current thread. - -$head thread$$ -The return value $icode thread$$ has prototype -$codei% - size_t %thread% -%$$ -and is the currently executing thread number. - -$head Example$$ -$cref thread_alloc.cpp$$ - -$end -*/ - /// Get current thread number - static size_t thread_num(void) - { return set_get_thread_num(CPPAD_NULL); } -/* ----------------------------------------------------------------------- -$begin ta_get_memory$$ -$spell - std - num - ptr - thread_alloc -$$ - -$section Get At Least A Specified Amount of Memory$$ -$mindex allocate$$ - - -$head Syntax$$ -$icode%v_ptr% = thread_alloc::get_memory(%min_bytes%, %cap_bytes%)%$$ - -$head Purpose$$ -Use $cref thread_alloc$$ to obtain a minimum number of bytes of memory -(for use by the $cref/current thread/ta_thread_num/$$). - -$head min_bytes$$ -This argument has prototype -$codei% - size_t %min_bytes% -%$$ -It specifies the minimum number of bytes to allocate. -This value must be less than -$codep - std::numeric_limits::max() / 2 -$$ - -$head cap_bytes$$ -This argument has prototype -$codei% - size_t& %cap_bytes% -%$$ -It's input value does not matter. -Upon return, it is the actual number of bytes (capacity) -that have been allocated for use, -$codei% - %min_bytes% <= %cap_bytes% -%$$ - -$head v_ptr$$ -The return value $icode v_ptr$$ has prototype -$codei% - void* %v_ptr% -%$$ -It is the location where the $icode cap_bytes$$ of memory -that have been allocated for use begins. - -$head Allocation Speed$$ -This allocation should be faster if the following conditions hold: -$list number$$ -The memory allocated by a previous call to $code get_memory$$ -is currently available for use. -$lnext -The current $icode min_bytes$$ is between -the previous $icode min_bytes$$ and previous $icode cap_bytes$$. -$lend - -$head Alignment$$ -We call a memory allocation aligned if the address is a multiple -of the number of bytes in a $code size_t$$ value. -If the system $code new$$ allocator is aligned, then $icode v_ptr$$ -pointer is also aligned. - -$head Example$$ -$cref thread_alloc.cpp$$ - -$end -*/ - /*! - Use thread_alloc to get a specified amount of memory. - - If the memory allocated by a previous call to \c get_memory is now - avaialable, and \c min_bytes is between its previous value - and the previous \c cap_bytes, this memory allocation will have - optimal speed. Otherwise, the memory allocation is more complicated and - may have to wait for other threads to complete an allocation. - - \param min_bytes [in] - The minimum number of bytes of memory to be obtained for use. - - \param cap_bytes [out] - The actual number of bytes of memory obtained for use. - - \return - pointer to the beginning of the memory allocated for use. - */ - static void* get_memory(size_t min_bytes, size_t& cap_bytes) - { // see first_trace below - CPPAD_ASSERT_FIRST_CALL_NOT_PARALLEL; - - // check that number of requested bytes is not to large - CPPAD_ASSERT_KNOWN( - min_bytes < std::numeric_limits::max() / 2 , - "get_memory(min_bytes, cap_bytes): min_bytes is too large" - ); - - size_t num_cap = capacity_info()->number; - using std::cout; - using std::endl; - - // determine the capacity for this request - size_t c_index = 0; - const size_t* capacity_vec = capacity_info()->value; - while( capacity_vec[c_index] < min_bytes ) - { ++c_index; - CPPAD_ASSERT_UNKNOWN(c_index < num_cap ); - } - cap_bytes = capacity_vec[c_index]; - - // determine the thread, capacity, and info for this thread - size_t thread = thread_num(); - size_t tc_index = thread * num_cap + c_index; - thread_alloc_info* info = thread_info(thread); - -# ifndef NDEBUG - // trace allocation - static bool first_trace = true; - if( cap_bytes == CPPAD_TRACE_CAPACITY && - thread == CPPAD_TRACE_THREAD && first_trace ) - { cout << endl; - cout << "thread_alloc: Trace for Thread = " << thread; - cout << " and capacity = " << cap_bytes << endl; - if( first_trace ) - first_trace = false; - } - - // Root nodes for both lists. Note these are different for different - // threads because tc_index is different for different threads. - block_t* inuse_root = info->root_inuse_ + c_index; -# endif - block_t* available_root = info->root_available_ + c_index; - - // check if we already have a node we can use - void* v_node = available_root->next_; - block_t* node = reinterpret_cast(v_node); - if( node != CPPAD_NULL ) - { CPPAD_ASSERT_UNKNOWN( node->tc_index_ == tc_index ); - - // remove node from available list - available_root->next_ = node->next_; - - // return value for get_memory - void* v_ptr = reinterpret_cast(node + 1); -# ifndef NDEBUG - // add node to inuse list - node->next_ = inuse_root->next_; - inuse_root->next_ = v_node; - - // trace allocation - if( cap_bytes == CPPAD_TRACE_CAPACITY && - thread == CPPAD_TRACE_THREAD ) - { cout << "get_memory: v_ptr = " << v_ptr << endl; } -# endif - - // adjust counts - inc_inuse(cap_bytes, thread); - dec_available(cap_bytes, thread); - - // return pointer to memory, do not inclue thread_alloc information - return v_ptr; - } - - // Create a new node with thread_alloc information at front. - // This uses the system allocator, which is thread safe, but slower, - // because the thread might wait for a lock on the allocator. - v_node = ::operator new(sizeof(block_t) + cap_bytes); - node = reinterpret_cast(v_node); - node->tc_index_ = tc_index; - void* v_ptr = reinterpret_cast(node + 1); - -# ifndef NDEBUG - // add node to inuse list - node->next_ = inuse_root->next_; - inuse_root->next_ = v_node; - - // trace allocation - if( cap_bytes == CPPAD_TRACE_CAPACITY && - thread == CPPAD_TRACE_THREAD ) - { cout << "get_memory: v_ptr = " << v_ptr << endl; } -# endif - - // adjust counts - inc_inuse(cap_bytes, thread); - - return v_ptr; - } - -/* ----------------------------------------------------------------------- -$begin ta_return_memory$$ -$spell - num - ptr - thread_alloc -$$ - -$section Return Memory to thread_alloc$$ -$mindex return_memory available$$ - - -$head Syntax$$ -$codei%thread_alloc::return_memory(%v_ptr%)%$$ - -$head Purpose$$ -If $cref/hold_memory/ta_hold_memory/$$ is false, -the memory is returned to the system. -Otherwise, the memory is retained by $cref thread_alloc$$ for quick future use -by the thread that allocated to memory. - -$head v_ptr$$ -This argument has prototype -$codei% - void* %v_ptr% -%$$. -It must be a pointer to memory that is currently in use; i.e. -obtained by a previous call to -$cref/get_memory/ta_get_memory/$$ and not yet returned. - -$head Thread$$ -Either the $cref/current thread/ta_thread_num/$$ must be the same as during -the corresponding call to $cref/get_memory/ta_get_memory/$$, -or the current execution mode must be sequential -(not $cref/parallel/ta_in_parallel/$$). - -$head NDEBUG$$ -If $code NDEBUG$$ is defined, $icode v_ptr$$ is not checked (this is faster). -Otherwise, a list of in use pointers is searched to make sure -that $icode v_ptr$$ is in the list. - -$head Example$$ -$cref thread_alloc.cpp$$ - -$end -*/ - /*! - Return memory that was obtained by \c get_memory. - If num_threads() == 1, - the memory is returned to the system. - Otherwise, it is retained by \c thread_alloc and available for use by - \c get_memory for this thread. - - \param v_ptr [in] - Value of the pointer returned by \c get_memory and still in use. - After this call, this pointer will available (and not in use). - - \par - We must either be in sequential (not parallel) execution mode, - or the current thread must be the same as for the corresponding call - to \c get_memory. - */ - static void return_memory(void* v_ptr) - { size_t num_cap = capacity_info()->number; - - block_t* node = reinterpret_cast(v_ptr) - 1; - size_t tc_index = node->tc_index_; - size_t thread = tc_index / num_cap; - size_t c_index = tc_index % num_cap; - size_t capacity = capacity_info()->value[c_index]; - - CPPAD_ASSERT_UNKNOWN( thread < CPPAD_MAX_NUM_THREADS ); - CPPAD_ASSERT_KNOWN( - thread == thread_num() || (! in_parallel()), - "Attempt to return memory for a different thread " - "while in parallel mode" - ); - - thread_alloc_info* info = thread_info(thread); -# ifndef NDEBUG - // remove node from inuse list - void* v_node = reinterpret_cast(node); - block_t* inuse_root = info->root_inuse_ + c_index; - block_t* previous = inuse_root; - while( (previous->next_ != CPPAD_NULL) & (previous->next_ != v_node) ) - previous = reinterpret_cast(previous->next_); - - // check that v_ptr is valid - if( previous->next_ != v_node ) - { using std::endl; - std::ostringstream oss; - oss << "return_memory: attempt to return memory not in use"; - oss << endl; - oss << "v_ptr = " << v_ptr << endl; - oss << "thread = " << thread << endl; - oss << "capacity = " << capacity << endl; - oss << "See CPPAD_TRACE_THREAD & CPPAD_TRACE_CAPACITY in"; - oss << endl << "%# include " << endl; - // oss.str() returns a string object with a copy of the current - // contents in the stream buffer. - std::string msg_str = oss.str(); - // msg_str.c_str() returns a pointer to the c-string - // representation of the string object's value. - const char* msg_char_star = msg_str.c_str(); - CPPAD_ASSERT_KNOWN(false, msg_char_star ); - } - - // trace option - if( capacity==CPPAD_TRACE_CAPACITY && thread==CPPAD_TRACE_THREAD ) - { std::cout << "return_memory: v_ptr = " << v_ptr << std::endl; } - - // remove v_ptr from inuse list - previous->next_ = node->next_; -# endif - // capacity bytes are removed from the inuse pool - dec_inuse(capacity, thread); - - // check for case where we just return the memory to the system - if( ! set_get_hold_memory(false) ) - { ::operator delete( reinterpret_cast(node) ); - return; - } - - // add this node to available list for this thread and capacity - block_t* available_root = info->root_available_ + c_index; - node->next_ = available_root->next_; - available_root->next_ = reinterpret_cast(node); - - // capacity bytes are added to the available pool - inc_available(capacity, thread); - } -/* ----------------------------------------------------------------------- -$begin ta_free_available$$ -$spell - num - thread_alloc -$$ - -$section Free Memory Currently Available for Quick Use by a Thread$$ -$mindex free_available$$ -$spell - inuse -$$ - - -$head Syntax$$ -$codei%thread_alloc::free_available(%thread%)%$$ - -$head Purpose$$ -Return to the system all the memory that is currently being -$cref/held/ta_hold_memory/$$ for quick use by the specified thread. - -$subhead Extra Memory$$ -In the case where $icode%thread% > 0%$$, -some extra memory is used to track allocations by the specified thread. -If -$codei% - thread_alloc::inuse(%thread%) == 0 -%$$ -the extra memory is also returned to the system. - -$head thread$$ -This argument has prototype -$codei% - size_t %thread% -%$$ -Either $cref/thread_num/ta_thread_num/$$ must be the same as $icode thread$$, -or the current execution mode must be sequential -(not $cref/parallel/ta_in_parallel/$$). - -$head Example$$ -$cref thread_alloc.cpp$$ - -$end -*/ - /*! - Return all the memory being held as available for a thread to the system. - - \param thread [in] - this thread that will no longer have any available memory after this call. - This must either be the thread currently executing, or we must be - in sequential (not parallel) execution mode. - */ - static void free_available(size_t thread) - { CPPAD_ASSERT_KNOWN( - thread < CPPAD_MAX_NUM_THREADS, - "Attempt to free memory for a thread >= CPPAD_MAX_NUM_THREADS" - ); - CPPAD_ASSERT_KNOWN( - thread == thread_num() || (! in_parallel()), - "Attempt to free memory for a different thread " - "while in parallel mode" - ); - - size_t num_cap = capacity_info()->number; - if( num_cap == 0 ) - return; - const size_t* capacity_vec = capacity_info()->value; - size_t c_index; - thread_alloc_info* info = thread_info(thread); - for(c_index = 0; c_index < num_cap; c_index++) - { size_t capacity = capacity_vec[c_index]; - block_t* available_root = info->root_available_ + c_index; - void* v_ptr = available_root->next_; - while( v_ptr != CPPAD_NULL ) - { block_t* node = reinterpret_cast(v_ptr); - void* next = node->next_; - ::operator delete(v_ptr); - v_ptr = next; - - dec_available(capacity, thread); - } - available_root->next_ = CPPAD_NULL; - } - CPPAD_ASSERT_UNKNOWN( available(thread) == 0 ); - if( inuse(thread) == 0 ) - { // clear the information for this thread - thread_info(thread, true); - } - } -/* ----------------------------------------------------------------------- -$begin ta_hold_memory$$ -$spell - alloc - num -$$ - -$section Control When Thread Alloc Retains Memory For Future Use$$ -$mindex hold$$ - -$head Syntax$$ -$codei%thread_alloc::hold_memory(%value%)%$$ - -$head Purpose$$ -It should be faster, even when $icode num_thread$$ is equal to one, -for $code thread_alloc$$ to hold onto memory. -Calling $icode hold_memory$$ with $icode value$$ equal to true, -instructs $code thread_alloc$$ to hold onto memory, -and put it in the $cref/available/ta_available/$$ pool, -after each call to $cref/return_memory/ta_return_memory/$$. - -$head value$$ -If $icode value$$ is true, -$code thread_alloc$$ with hold onto memory for future quick use. -If it is false, future calls to $cref/return_memory/ta_return_memory/$$ -will return the corresponding memory to the system. -By default (when $code hold_memory$$ has not been called) -$code thread_alloc$$ does not hold onto memory. - -$head free_available$$ -Memory that is being held by $code thread_alloc$$ can be returned -to the system using $cref/free_available/ta_free_available/$$. - -$end -*/ - /*! - Change the thread_alloc hold memory setting. - - \param value [in] - New value for the thread_alloc hold memory setting. - */ - static void hold_memory(bool value) - { bool set = true; - set_get_hold_memory(set, value); - } - -/* ----------------------------------------------------------------------- -$begin ta_inuse$$ -$spell - num - inuse - thread_alloc -$$ - -$section Amount of Memory a Thread is Currently Using$$ -$mindex inuse$$ - - -$head Syntax$$ -$icode%num_bytes% = thread_alloc::inuse(%thread%)%$$ - -$head Purpose$$ -Memory being managed by $cref thread_alloc$$ has two states, -currently in use by the specified thread, -and quickly available for future use by the specified thread. -This function informs the program how much memory is in use. - -$head thread$$ -This argument has prototype -$codei% - size_t %thread% -%$$ -Either $cref/thread_num/ta_thread_num/$$ must be the same as $icode thread$$, -or the current execution mode must be sequential -(not $cref/parallel/ta_in_parallel/$$). - -$head num_bytes$$ -The return value has prototype -$codei% - size_t %num_bytes% -%$$ -It is the number of bytes currently in use by the specified thread. - -$head Example$$ -$cref thread_alloc.cpp$$ - -$end -*/ - /*! - Determine the amount of memory that is currently inuse. - - \param thread [in] - Thread for which we are determining the amount of memory - (must be < CPPAD_MAX_NUM_THREADS). - Durring parallel execution, this must be the thread - that is currently executing. - - \return - The amount of memory in bytes. - */ - static size_t inuse(size_t thread) - { - CPPAD_ASSERT_UNKNOWN( thread < CPPAD_MAX_NUM_THREADS); - CPPAD_ASSERT_UNKNOWN( - thread == thread_num() || (! in_parallel()) - ); - thread_alloc_info* info = thread_info(thread); - return info->count_inuse_; - } -/* ----------------------------------------------------------------------- -$begin ta_available$$ -$spell - num - thread_alloc -$$ - -$section Amount of Memory Available for Quick Use by a Thread$$ - - -$head Syntax$$ -$icode%num_bytes% = thread_alloc::available(%thread%)%$$ - -$head Purpose$$ -Memory being managed by $cref thread_alloc$$ has two states, -currently in use by the specified thread, -and quickly available for future use by the specified thread. -This function informs the program how much memory is available. - -$head thread$$ -This argument has prototype -$codei% - size_t %thread% -%$$ -Either $cref/thread_num/ta_thread_num/$$ must be the same as $icode thread$$, -or the current execution mode must be sequential -(not $cref/parallel/ta_in_parallel/$$). - -$head num_bytes$$ -The return value has prototype -$codei% - size_t %num_bytes% -%$$ -It is the number of bytes currently available for use by the specified thread. - -$head Example$$ -$cref thread_alloc.cpp$$ - -$end -*/ - /*! - Determine the amount of memory that is currently available for use. - - \copydetails inuse - */ - static size_t available(size_t thread) - { - CPPAD_ASSERT_UNKNOWN( thread < CPPAD_MAX_NUM_THREADS); - CPPAD_ASSERT_UNKNOWN( - thread == thread_num() || (! in_parallel()) - ); - thread_alloc_info* info = thread_info(thread); - return info->count_available_; - } -/* ----------------------------------------------------------------------- -$begin ta_create_array$$ -$spell - inuse - thread_alloc - sizeof -$$ - -$section Allocate An Array and Call Default Constructor for its Elements$$ -$mindex create_array$$ - - -$head Syntax$$ -$icode%array% = thread_alloc::create_array<%Type%>(%size_min%, %size_out%)%$$. - -$head Purpose$$ -Create a new raw array using $cref thread_alloc$$ memory allocator -(works well in a multi-threading environment) -and call default constructor for each element. - -$head Type$$ -The type of the elements of the array. - -$head size_min$$ -This argument has prototype -$codei% - size_t %size_min% -%$$ -This is the minimum number of elements that there can be -in the resulting $icode array$$. - -$head size_out$$ -This argument has prototype -$codei% - size_t& %size_out% -%$$ -The input value of this argument does not matter. -Upon return, it is the actual number of elements -in $icode array$$ -($icode% size_min %<=% size_out%$$). - -$head array$$ -The return value $icode array$$ has prototype -$codei% - %Type%* %array% -%$$ -It is array with $icode size_out$$ elements. -The default constructor for $icode Type$$ is used to initialize the -elements of $icode array$$. -Note that $cref/delete_array/ta_delete_array/$$ -should be used to destroy the array when it is no longer needed. - -$head Delta$$ -The amount of memory $cref/inuse/ta_inuse/$$ by the current thread, -will increase $icode delta$$ where -$codei% - sizeof(%Type%) * (%size_out% + 1) > %delta% >= sizeof(%Type%) * %size_out% -%$$ -The $cref/available/ta_available/$$ memory will decrease by $icode delta$$, -(and the allocation will be faster) -if a previous allocation with $icode size_min$$ between its current value -and $icode size_out$$ is available. - -$head Alignment$$ -We call a memory allocation aligned if the address is a multiple -of the number of bytes in a $code size_t$$ value. -If the system $code new$$ allocator is aligned, then $icode array$$ -pointer is also aligned. - -$head Example$$ -$cref thread_alloc.cpp$$ - -$end -*/ - /*! - Use thread_alloc to allocate an array, then call default construtor - for each element. - - \tparam Type - The type of the elements of the array. - - \param size_min [in] - The minimum number of elements in the array. - - \param size_out [out] - The actual number of elements in the array. - - \return - pointer to the first element of the array. - The default constructor is used to initialize - all the elements of the array. - - \par - The \c extra_ field, in the \c thread_alloc node before the return value, - is set to size_out. - */ - template - static Type* create_array(size_t size_min, size_t& size_out) - { // minimum number of bytes to allocate - size_t min_bytes = size_min * sizeof(Type); - // do the allocation - size_t num_bytes; - void* v_ptr = get_memory(min_bytes, num_bytes); - // This is where the array starts - Type* array = reinterpret_cast(v_ptr); - // number of Type values in the allocation - size_out = num_bytes / sizeof(Type); - // store this number in the extra field - block_t* node = reinterpret_cast(v_ptr) - 1; - node->extra_ = size_out; - - // call default constructor for each element - size_t i; - for(i = 0; i < size_out; i++) - new(array + i) Type(); - - return array; - } -/* ----------------------------------------------------------------------- -$begin ta_delete_array$$ -$spell - inuse - thread_alloc - sizeof - deallocate -$$ - -$section Deallocate An Array and Call Destructor for its Elements$$ -$mindex delete_array$$ - - -$head Syntax$$ -$codei%thread_alloc::delete_array(%array%)%$$. - -$head Purpose$$ -Returns memory corresponding to an array created by -(create by $cref/create_array/ta_create_array/$$) to the -$cref/available/ta_available/$$ memory pool for the current thread. - -$head Type$$ -The type of the elements of the array. - -$head array$$ -The argument $icode array$$ has prototype -$codei% - %Type%* %array% -%$$ -It is a value returned by $cref/create_array/ta_create_array/$$ and not yet deleted. -The $icode Type$$ destructor is called for each element in the array. - -$head Thread$$ -The $cref/current thread/ta_thread_num/$$ must be the -same as when $cref/create_array/ta_create_array/$$ returned the value $icode array$$. -There is an exception to this rule: -when the current execution mode is sequential -(not $cref/parallel/ta_in_parallel/$$) the current thread number does not matter. - -$head Delta$$ -The amount of memory $cref/inuse/ta_inuse/$$ will decrease by $icode delta$$, -and the $cref/available/ta_available/$$ memory will increase by $icode delta$$, -where $cref/delta/ta_create_array/Delta/$$ -is the same as for the corresponding call to $code create_array$$. - -$head Example$$ -$cref thread_alloc.cpp$$ - -$end -*/ - /*! - Return Memory Used for an Array to the Available Pool - (include destructor call for each element). - - \tparam Type - The type of the elements of the array. - - \param array [in] - A value returned by \c create_array that has not yet been deleted. - The \c Type destructor is used to destroy each of the elements - of the array. - - \par - Durring parallel execution, the current thread must be the same - as during the corresponding call to \c create_array. - */ - template - static void delete_array(Type* array) - { // determine the number of values in the array - block_t* node = reinterpret_cast(array) - 1; - size_t size = node->extra_; - - // call destructor for each element - size_t i; - for(i = 0; i < size; i++) - (array + i)->~Type(); - - // return the memory to the available pool for this thread - thread_alloc::return_memory( reinterpret_cast(array) ); - } -/* ----------------------------------------------------------------------- -$begin ta_free_all$$ -$spell - alloc - bool - inuse -$$ - -$section Free All Memory That Was Allocated for Use by thread_alloc$$ - - -$head Syntax$$ -$icode%ok% = thread_alloc::free_all()%$$. - -$head Purpose$$ -Returns all memory that was used by $code thread_alloc$$ to the system. - -$head ok$$ -The return value $icode ok$$ has prototype -$codei% - bool %ok% -%$$ -Its value will be $code true$$ if all the memory can be freed. -This requires that for all $icode thread$$ indices, there is no memory -$cref/inuse/ta_inuse/$$; i.e., -$codei% - 0 == thread_alloc::inuse(%thread%) -%$$ -Otherwise, the return value will be false. - -$head Restrictions$$ -This function cannot be called while in parallel mode. - -$head Example$$ -$cref thread_alloc.cpp$$ -$end -*/ - /*! - Return to the system all thread_alloc memory that is not currently inuse. - - \return - If no \c thread_alloc memory is currently inuse, - all memory is returned to the system and the return value is true. - Otherwise the return value is false. - */ - static bool free_all(void) - { CPPAD_ASSERT_KNOWN( - ! in_parallel(), - "free_all cannot be used while in parallel execution" - ); - bool ok = true; - size_t thread = CPPAD_MAX_NUM_THREADS; - while(thread--) - { ok &= inuse(thread) == 0; - free_available(thread); - } - return ok; - } -}; - - -} // END_CPPAD_NAMESPACE - -// preprocessor symbols local to this file -# undef CPPAD_MAX_NUM_CAPACITY -# undef CPPAD_MIN_DOUBLE_CAPACITY -# undef CPPAD_TRACE_CAPACITY -# undef CPPAD_TRACE_THREAD -# endif diff --git a/ct_core/include/ct/external/cppad/utility/time_test.hpp b/ct_core/include/ct/external/cppad/utility/time_test.hpp deleted file mode 100644 index ab2c3d158..000000000 --- a/ct_core/include/ct/external/cppad/utility/time_test.hpp +++ /dev/null @@ -1,233 +0,0 @@ -// $Id: time_test.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_TIME_TEST_HPP -# define CPPAD_TIME_TEST_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin time_test$$ -$spell - gettimeofday - vec - cppad.hpp - Microsoft - namespace - std - const - cout - ctime - ifdef - const - endif - cpp -$$ - - -$section Determine Amount of Time to Execute a Test$$ -$mindex time_test speed$$ - -$head Syntax$$ -$codei%# include -%$$ -$icode%time% = time_test(%test%, %time_min%)%$$ -$icode%time% = time_test(%test%, %time_min%, %test_size%)%$$ - -$head Purpose$$ -The $code time_test$$ function executes a timing test -and reports the amount of wall clock time for execution. - -$head Motivation$$ -It is important to separate small calculation units -and test them individually. -This way individual changes can be tested in the context of the -routine that they are in. -On many machines, accurate timing of a very short execution -sequences is not possible. -In addition, -there may be set up and tear down time for a test that -we do not really want included in the timing. -For this reason $code time_test$$ -automatically determines how many times to -repeat the section of the test that we wish to time. - -$head Include$$ -The file $code cppad/time_test.hpp$$ defines the -$code time_test$$ function. -This file is included by $code cppad/cppad.hpp$$ -and it can also be included separately with out the rest of -the $code CppAD$$ routines. - -$head test$$ -The $code time_test$$ argument $icode test$$ is a function, -or function object. -In the case where $icode test_size$$ is not present, -$icode test$$ supports the syntax -$codei% - %test%(%repeat%) -%$$ -In the case where $icode test_size$$ is present, -$icode test$$ supports the syntax -$codei% - %test%(%size%, %repeat%) -%$$ -In either case, the return value for $icode test$$ is $code void$$. - -$subhead size$$ -If the argument $icode size$$ is present, -it has prototype -$codei% - size_t %size% -%$$ -and is equal to the $icode test_size$$ argument to $code time_test$$. - -$subhead repeat$$ -The $icode test$$ argument $icode repeat$$ has prototype -$codei% - size_t %repeat% -%$$ -It will be equal to the $icode size$$ argument to $code time_test$$. - -$head time_min$$ -The argument $icode time_min$$ has prototype -$codei% - double %time_min% -%$$ -It specifies the minimum amount of time in seconds -that the $icode test$$ routine should take. -The $icode repeat$$ argument to $icode test$$ is increased -until this amount of execution time (or more) is reached. - -$head test_size$$ -This argument has prototype -$codei% - size_t %test_size% -%$$ -It specifies the $icode size$$ argument to $icode test$$. - -$head time$$ -The return value $icode time$$ has prototype -$codei% - double %time% -%$$ -and is the number of wall clock seconds that it took -to execute $icode test$$ divided by the value used for $icode repeat$$. - -$head Timing$$ -The routine $cref elapsed_seconds$$ will be used to determine the -amount of time it took to execute the test. - -$children% - cppad/utility/elapsed_seconds.hpp% - speed/example/time_test.cpp -%$$ -$head Example$$ -The routine $cref time_test.cpp$$ is an example and test -of $code time_test$$. - -$end ------------------------------------------------------------------------ -*/ - -# include -# include -# include -# include -# include - -# define CPPAD_EXTRA_RUN_BEFORE_TIMING 0 - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file time_test.hpp -\brief Function that preforms one timing test (for speed of execution). -*/ - -/*! -Preform one wall clock execution timing test. - -\tparam Test -Either the type void (*)(size_t) or a function object -type that supports the same syntax. - -\param test -The function, or function object, that supports the operation -test(repeat) where \c repeat is the number of times -to repeat the tests operaiton that is being timed. - -\param time_min -is the minimum amount of time that \c test should take to preform -the repetitions of the operation being timed. -*/ -template -double time_test(Test test, double time_min ) -{ -# if CPPAD_EXTRA_RUN_BEFORE_TIMING - test(1); -# endif - size_t repeat = 0; - double s0 = elapsed_seconds(); - double s1 = s0; - while( s1 - s0 < time_min ) - { repeat = std::max(size_t(1), 2 * repeat); - s0 = elapsed_seconds(); - test(repeat); - s1 = elapsed_seconds(); - } - double time = (s1 - s0) / double(repeat); - return time; -} - -/*! -Preform one wall clock execution timing test. - -\tparam Test -Either the type void (*)(size_t, size_t) or a function object -type that supports the same syntax. - -\param test -The function, or function object, that supports the operation -test(size, repeat) where -\c is the size for this test and -\c repeat is the number of times -to repeat the tests operaiton that is being timed. - -\param time_min -is the minimum amount of time that \c test should take to preform -the repetitions of the operation being timed. - -\param test_size -will be used for the value of \c size in the call to \c test. -*/ -template -double time_test(Test test, double time_min, size_t test_size) -{ -# if CPPAD_EXTRA_RUN_BEFORE_TIMING - test(test_size, 1); -# endif - size_t repeat = 0; - double s0 = elapsed_seconds(); - double s1 = s0; - while( s1 - s0 < time_min ) - { repeat = std::max(size_t(1), 2 * repeat); - s0 = elapsed_seconds(); - test(test_size, repeat); - s1 = elapsed_seconds(); - } - double time = (s1 - s0) / double(repeat); - return time; -} - -} // END_CPPAD_NAMESPACE - -# undef CPPAD_EXTRA_RUN_BEFORE_TIMING -// END PROGRAM -# endif diff --git a/ct_core/include/ct/external/cppad/utility/to_string.hpp b/ct_core/include/ct/external/cppad/utility/to_string.hpp deleted file mode 100644 index 62d28ae5f..000000000 --- a/ct_core/include/ct/external/cppad/utility/to_string.hpp +++ /dev/null @@ -1,172 +0,0 @@ -// $Id$ -# ifndef CPPAD_TO_STRING_HPP -# define CPPAD_TO_STRING_HPP -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin to_string$$ -$spell - cppad.hpp - long long - std - const - ostringstream -$$ - -$section Convert Certain Types to a String$$ - -$head Syntax$$ -$codei%# include -%$$ -$icode%s% = to_string(%value%)%$$. - -$head See Also$$ -$cref base_to_string$$, $cref ad_to_string$$ - -$head Purpose$$ -This routine is similar to the C++11 routine $code std::to_string$$ -with the following differences: -$list number$$ -It works with C++98. -$lnext -It has been extended to the fundamental floating point types. -$lnext -It has specifications for extending to an arbitrary type; see -$cref base_to_string$$. -$lnext -If $code $$ is included, -and it has been extended to a $icode Base$$ type, -it automatically extends to the -$cref/AD types above Base/glossary/AD Type Above Base/$$. -$lend - -$head value$$ - -$subhead Integer$$ -The argument $icode value$$ can have the following prototype -$codei% - const %Integer%& %value% -%$$ -where $icode Integer$$ is any of the fundamental integer types; e.g., -$code short int$$ and $code unsigned long$$. -Note that if C++11 is supported by this compilation, -$code unsigned long long$$ is also a fundamental integer type. - -$subhead Float$$ -The argument $icode value$$ can have the following prototype -$codei% - const %Float%& %value% -%$$ -where $icode Float$$ is any of the fundamental floating point types; i.e., -$code float$$, $code double$$, and $code long double$$. - -$head s$$ -The return value has prototype -$codei% - std::string %s% -%$$ -and contains a representation of the specified $icode value$$. - -$subhead Integer$$ -If $icode value$$ is an $codei Integer$$, -the representation is equivalent to $codei%os% << %value%$$ -where $icode os$$ is an $code std::ostringstream$$. - -$subhead Float$$ -If $icode value$$ is a $codei Float$$, -enough digits are used in the representation so that -the result is accurate to withing round off error. - -$children% - example/to_string.cpp -%$$ -$head Example$$ -The file $cref to_string.cpp$$ -contains an example and test of this routine. -It returns true if it succeeds and false otherwise. - -$end -*/ -# include -# include -# include -# include -# include - -# define CPPAD_SPECIALIZE_TO_STRING_INTEGER(Type) \ -template <> struct to_string_struct\ -{ std::string operator()(const Type& value) \ - { std::stringstream os;\ - os << value;\ - return os.str();\ - }\ -}; - -# define CPPAD_SPECIALIZE_TO_STRING_FLOAT(Float) \ -template <> struct to_string_struct\ -{ std::string operator()(const Float& value) \ - { std::stringstream os;\ - Float epsilon = std::numeric_limits::epsilon();\ - size_t n_digits = 1 - int( std::log10(epsilon) );\ - os << std::setprecision(n_digits);\ - os << value;\ - return os.str();\ - }\ -}; - -namespace CppAD { - - // Default implementation, - // each type must define its own specilization. - template - struct to_string_struct - { std::string operator()(const Type& value) - { CPPAD_ASSERT_KNOWN( - false, - "to_string is not implemented for this type" - ); - // return empty string - return std::string(""); - } - }; - - // specialization for the fundamental integer types - CPPAD_SPECIALIZE_TO_STRING_INTEGER(signed short) - CPPAD_SPECIALIZE_TO_STRING_INTEGER(unsigned short) - // - CPPAD_SPECIALIZE_TO_STRING_INTEGER(signed int) - CPPAD_SPECIALIZE_TO_STRING_INTEGER(unsigned int) - // - CPPAD_SPECIALIZE_TO_STRING_INTEGER(signed long) - CPPAD_SPECIALIZE_TO_STRING_INTEGER(unsigned long) - // -# if CPPAD_USE_CPLUSPLUS_2011 - CPPAD_SPECIALIZE_TO_STRING_INTEGER(signed long long) - CPPAD_SPECIALIZE_TO_STRING_INTEGER(unsigned long long) -# endif - - // specialization for the fundamental floating point types - CPPAD_SPECIALIZE_TO_STRING_FLOAT(float) - CPPAD_SPECIALIZE_TO_STRING_FLOAT(double) - CPPAD_SPECIALIZE_TO_STRING_FLOAT(long double) - - // link from function to function object in structure - template - std::string to_string(const Type& value) - { to_string_struct to_str; - return to_str(value); - } -} - -# undef CPPAD_SPECIALIZE_TO_STRING_FLOAT -# undef CPPAD_SPECIALIZE_TO_STRING_INTEGER -# endif diff --git a/ct_core/include/ct/external/cppad/utility/track_new_del.hpp b/ct_core/include/ct/external/cppad/utility/track_new_del.hpp deleted file mode 100644 index 7acff0c94..000000000 --- a/ct_core/include/ct/external/cppad/utility/track_new_del.hpp +++ /dev/null @@ -1,543 +0,0 @@ -// $Id: track_new_del.hpp 3769 2015-12-29 16:13:16Z bradbell $ -# ifndef CPPAD_TRACK_NEW_DEL_HPP -# define CPPAD_TRACK_NEW_DEL_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ -/* -$begin TrackNewDel$$ -$spell - cppad.hpp - Cpp - newptr - Vec - oldptr - newlen - ncopy - const -$$ - -$section Routines That Track Use of New and Delete$$ -$mindex memory NDEBUG CPPAD_TRACK_NEW_VEC CppADTrackNewVec CPPAD_TRACK_DEL_VEC CppADTrackDelVec CPPAD_TRACK_EXTEND CppADTrackExtend CPPAD_TRACK_COUNT thread multi$$ - -$head Deprecated 2007-07-23$$ -All these routines have been deprecated. -You should use the $cref thread_alloc$$ memory allocator instead -(which works better in both a single thread and -properly in multi-threading environment). - -$head Syntax$$ -$codei%# include -%$$ -$icode%newptr% = TrackNewVec(%file%, %line%, %newlen%, %oldptr%) -%$$ -$codei%TrackDelVec(%file%, %line%, %oldptr%) -%$$ -$icode%newptr% = TrackExtend(%file%, %line%, %newlen%, %ncopy%, %oldptr%) -%$$ -$icode%count% = TrackCount(%file%, %line%)%$$ - - -$head Purpose$$ -These routines -aid in the use of $code new[]$$ and $code delete[]$$ -during the execution of a C++ program. - -$head Include$$ -The file $code cppad/track_new_del.hpp$$ is included by -$code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of the -CppAD include files. - - -$head file$$ -The argument $icode file$$ has prototype -$codei% - const char *%file% -%$$ -It should be the source code file name -where the call to $code TrackNew$$ is located. -The best way to accomplish this is the use the preprocessor symbol -$code __FILE__$$ for this argument. - -$head line$$ -The argument $icode line$$ has prototype -$codei% - int %line% -%$$ -It should be the source code file line number -where the call to $code TrackNew$$ is located. -The best way to accomplish this is the use the preprocessor symbol -$code __LINE__$$ for this argument. - -$head oldptr$$ -The argument $icode oldptr$$ has prototype -$codei% - %Type% *%oldptr% -%$$ -This argument is used to identify the type $icode Type$$. - -$head newlen$$ -The argument $icode newlen$$ has prototype -$codei% - size_t %newlen% -%$$ - -$head head newptr$$ -The return value $icode newptr$$ has prototype -$codei% - %Type% *%newptr% -%$$ -It points to the newly allocated vector of objects -that were allocated using -$codei% - new Type[%newlen%] -%$$ - -$head ncopy$$ -The argument $icode ncopy$$ has prototype -$codei% - size_t %ncopy% -%$$ -This specifies the number of elements that are copied from -the old array to the new array. -The value of $icode ncopy$$ -must be less than or equal $icode newlen$$. - -$head TrackNewVec$$ -If $code NDEBUG$$ is defined, this routine only sets -$codei% - %newptr% = %Type% new[%newlen%] -%$$ -The value of $icode oldptr$$ does not matter -(except that it is used to identify $icode Type$$). -If $code NDEBUG$$ is not defined, $code TrackNewVec$$ also -tracks the this memory allocation. -In this case, if memory cannot be allocated -$cref ErrorHandler$$ is used to generate a message -stating that there was not sufficient memory. - -$subhead Macro$$ -The preprocessor macro call -$codei% - CPPAD_TRACK_NEW_VEC(%newlen%, %oldptr%) -%$$ -expands to -$codei% - CppAD::TrackNewVec(__FILE__, __LINE__, %newlen%, %oldptr%) -%$$ - -$subhead Previously Deprecated$$ -The preprocessor macro $code CppADTrackNewVec$$ is the -same as $code CPPAD_TRACK_NEW_VEC$$ and was previously deprecated. - -$head TrackDelVec$$ -This routine is used to a vector of objects -that have been allocated using $code TrackNew$$ or $code TrackExtend$$. -If $code NDEBUG$$ is defined, this routine only frees memory with -$codei% - delete [] %oldptr% -%$$ -If $code NDEBUG$$ is not defined, $code TrackDelete$$ also checks that -$icode oldptr$$ was allocated by $code TrackNew$$ or $code TrackExtend$$ -and has not yet been freed. -If this is not the case, -$cref ErrorHandler$$ is used to generate an error message. - -$subhead Macro$$ -The preprocessor macro call -$codei% - CPPAD_TRACK_DEL_VEC(%oldptr%) -%$$ -expands to -$codei% - CppAD::TrackDelVec(__FILE__, __LINE__, %oldptr%) -%$$ - -$subhead Previously Deprecated$$ -The preprocessor macro $code CppADTrackDelVec$$ is the -same as $code CPPAD_TRACK_DEL_VEC$$ was previously deprecated. - -$head TrackExtend$$ -This routine is used to -allocate a new vector (using $code TrackNewVec$$), -copy $icode ncopy$$ elements from the old vector to the new vector. -If $icode ncopy$$ is greater than zero, $icode oldptr$$ -must have been allocated using $code TrackNewVec$$ or $code TrackExtend$$. -In this case, the vector pointed to by $icode oldptr$$ -must be have at least $icode ncopy$$ elements -and it will be deleted (using $code TrackDelVec$$). -Note that the dependence of $code TrackExtend$$ on $code NDEBUG$$ -is indirectly through the routines $code TrackNewVec$$ and -$code TrackDelVec$$. - -$subhead Macro$$ -The preprocessor macro call -$codei% - CPPAD_TRACK_EXTEND(%newlen%, %ncopy%, %oldptr%) -%$$ -expands to -$codei% - CppAD::TrackExtend(__FILE__, __LINE__, %newlen%, %ncopy%, %oldptr%) -%$$ - -$subhead Previously Deprecated$$ -The preprocessor macro $code CppADTrackExtend$$ is the -same as $code CPPAD_TRACK_EXTEND$$ and was previously deprecated. - -$head TrackCount$$ -The return value $icode count$$ has prototype -$codei% - size_t %count% -%$$ -If $code NDEBUG$$ is defined, $icode count$$ will be zero. -Otherwise, it will be -the number of vectors that -have been allocated -(by $code TrackNewVec$$ or $code TrackExtend$$) -and not yet freed -(by $code TrackDelete$$). - -$subhead Macro$$ -The preprocessor macro call -$codei% - CPPAD_TRACK_COUNT() -%$$ -expands to -$codei% - CppAD::TrackCount(__FILE__, __LINE__) -%$$ - -$subhead Previously Deprecated$$ -The preprocessor macro $code CppADTrackCount$$ is the -same as $code CPPAD_TRACK_COUNT$$ and was previously deprecated. - -$head Multi-Threading$$ -These routines cannot be used $cref/in_parallel/ta_in_parallel/$$ -execution mode. -Use the $cref thread_alloc$$ routines instead. - -$head Example$$ -$children% - test_more/track_new_del.cpp -%$$ -The file $cref TrackNewDel.cpp$$ -contains an example and test of these functions. -It returns true, if it succeeds, and false otherwise. - -$end ------------------------------------------------------------------------------- -*/ -# include -# include -# include -# include -# include - -# ifndef CPPAD_TRACK_DEBUG -# define CPPAD_TRACK_DEBUG 0 -# endif - -// ------------------------------------------------------------------------- -# define CPPAD_TRACK_NEW_VEC(newlen, oldptr) \ - CppAD::TrackNewVec(__FILE__, __LINE__, newlen, oldptr) - -# define CPPAD_TRACK_DEL_VEC(oldptr) \ - CppAD::TrackDelVec(__FILE__, __LINE__, oldptr) - -# define CPPAD_TRACK_EXTEND(newlen, ncopy, oldptr) \ - CppAD::TrackExtend(__FILE__, __LINE__, newlen, ncopy, oldptr) - -# define CPPAD_TRACK_COUNT() \ - CppAD::TrackCount(__FILE__, __LINE__) -// ------------------------------------------------------------------------- -# define CppADTrackNewVec CPPAD_TRACK_NEW_VEC -# define CppADTrackDelVec CPPAD_TRACK_DEL_VEC -# define CppADTrackExtend CPPAD_TRACK_EXTEND -# define CppADTrackCount CPPAD_TRACK_COUNT -// ------------------------------------------------------------------------- -namespace CppAD { // Begin CppAD namespace - -// TrackElement ------------------------------------------------------------ -class TrackElement { - -public: - std::string file; // corresponding file name - int line; // corresponding line number - void *ptr; // value returned by TrackNew - TrackElement *next; // next element in linked list - - // default contructor (used to initialize root) - TrackElement(void) - : file(""), line(0), ptr(CPPAD_NULL), next(CPPAD_NULL) - { } - - TrackElement(const char *f, int l, void *p) - : file(f), line(l), ptr(p), next(CPPAD_NULL) - { CPPAD_ASSERT_UNKNOWN( p != CPPAD_NULL); - } - - // There is only one tracking list and it starts it here - static TrackElement *Root(void) - { CPPAD_ASSERT_UNKNOWN( ! thread_alloc::in_parallel() ); - static TrackElement root; - return &root; - } - - // Print one tracking element - static void Print(TrackElement* E) - { - CPPAD_ASSERT_UNKNOWN( ! thread_alloc::in_parallel() ); - using std::cout; - cout << "E = " << E; - cout << ", E->next = " << E->next; - cout << ", E->ptr = " << E->ptr; - cout << ", E->line = " << E->line; - cout << ", E->file = " << E->file; - cout << std::endl; - } - - // Print the linked list for a thread - static void Print(void) - { - CPPAD_ASSERT_UNKNOWN( ! thread_alloc::in_parallel() ); - using std::cout; - using std::endl; - TrackElement *E = Root(); - // convert int(size_t) to avoid warning on _MSC_VER systems - cout << "Begin Track List" << endl; - while( E->next != CPPAD_NULL ) - { E = E->next; - Print(E); - } - cout << "End Track List:" << endl; - cout << endl; - } -}; - - -// TrackError ---------------------------------------------------------------- -inline void TrackError( - const char *routine, - const char *file, - int line, - const char *msg ) -{ - CPPAD_ASSERT_UNKNOWN( ! thread_alloc::in_parallel() ); - std::ostringstream buf; - buf << routine - << ": at line " - << line - << " in file " - << file - << std::endl - << msg; - std::string str = buf.str(); - size_t n = str.size(); - size_t i; - char *message = new char[n + 1]; - for(i = 0; i < n; i++) - message[i] = str[i]; - message[n] = '\0'; - CPPAD_ASSERT_KNOWN( false , message); -} - -// TrackNewVec --------------------------------------------------------------- -# ifdef NDEBUG -template -inline Type *TrackNewVec( - const char *file, int line, size_t len, Type * /* oldptr */ ) -{ -# if CPPAD_TRACK_DEBUG - static bool first = true; - if( first ) - { std::cout << "NDEBUG is defined for TrackNewVec" << std::endl; - first = false; - } -# endif - return (new Type[len]); -} - -# else - -template -Type *TrackNewVec( - const char *file , - int line , - size_t len , - Type * /* oldptr */ ) -{ - CPPAD_ASSERT_KNOWN( - ! thread_alloc::in_parallel() , - "attempt to use TrackNewVec in parallel execution mode." - ); - // try to allocate the new memrory - Type *newptr = CPPAD_NULL; - try - { newptr = new Type[len]; - } - catch(...) - { TrackError("TrackNewVec", file, line, - "Cannot allocate sufficient memory" - ); - } - // create tracking element - void *vptr = static_cast(newptr); - TrackElement *E = new TrackElement(file, line, vptr); - - // get the root - TrackElement *root = TrackElement::Root(); - - // put this elemenent at the front of linked list - E->next = root->next; - root->next = E; - -# if CPPAD_TRACK_DEBUG - std::cout << "TrackNewVec: "; - TrackElement::Print(E); -# endif - - return newptr; -} - -# endif - -// TrackDelVec -------------------------------------------------------------- -# ifdef NDEBUG -template -inline void TrackDelVec(const char *file, int line, Type *oldptr) -{ -# if CPPAD_TRACK_DEBUG - static bool first = true; - if( first ) - { std::cout << "NDEBUG is defined in TrackDelVec" << std::endl; - first = false; - } -# endif - delete [] oldptr; -} - -# else - -template -void TrackDelVec( - const char *file , - int line , - Type *oldptr ) -{ - CPPAD_ASSERT_KNOWN( - ! thread_alloc::in_parallel() , - "attempt to use TrackDelVec in parallel execution mode." - ); - TrackElement *P; - TrackElement *E; - - // search list for pointer - P = TrackElement::Root(); - E = P->next; - void *vptr = static_cast(oldptr); - while(E != CPPAD_NULL && E->ptr != vptr) - { P = E; - E = E->next; - } - - // check if pointer was not in list - if( E == CPPAD_NULL || E->ptr != vptr ) TrackError( - "TrackDelVec", file, line, - "Invalid value for the argument oldptr.\n" - "Possible linking of debug and NDEBUG compilations of CppAD." - ); - -# if CPPAD_TRACK_DEBUG - std::cout << "TrackDelVec: "; - TrackElement::Print(E); -# endif - - // remove tracking element from list - P->next = E->next; - - // delete allocated pointer - delete [] oldptr; - - // delete tracking element - delete E; - - return; -} - -# endif - -// TrackExtend -------------------------------------------------------------- -template -Type *TrackExtend( - const char *file , - int line , - size_t newlen , - size_t ncopy , - Type *oldptr ) -{ - CPPAD_ASSERT_KNOWN( - ! thread_alloc::in_parallel() , - "attempt to use TrackExtend in parallel execution mode." - ); - -# if CPPAD_TRACK_DEBUG - using std::cout; - cout << "TrackExtend: file = " << file; - cout << ", line = " << line; - cout << ", newlen = " << newlen; - cout << ", ncopy = " << ncopy; - cout << ", oldptr = " << oldptr; - cout << std::endl; -# endif - CPPAD_ASSERT_KNOWN( - ncopy <= newlen, - "TrackExtend: ncopy is greater than newlen." - ); - - // allocate the new memrory - Type *newptr = TrackNewVec(file, line, newlen, oldptr); - - // copy the data - size_t i; - for(i = 0; i < ncopy; i++) - newptr[i] = oldptr[i]; - - // delete the old vector - if( ncopy > 0 ) - TrackDelVec(file, line, oldptr); - - return newptr; -} - -// TrackCount -------------------------------------------------------------- -inline size_t TrackCount(const char *file, int line) -{ - CPPAD_ASSERT_KNOWN( - ! thread_alloc::in_parallel() , - "attempt to use TrackCount in parallel execution mode." - ); - size_t count = 0; - TrackElement *E = TrackElement::Root(); - while( E->next != CPPAD_NULL ) - { ++count; - E = E->next; - } - return count; -} -// --------------------------------------------------------------------------- - -} // End CppAD namespace - -// preprocessor symbols local to this file -# undef CPPAD_TRACK_DEBUG - -# endif diff --git a/ct_core/include/ct/external/cppad/utility/vector.hpp b/ct_core/include/ct/external/cppad/utility/vector.hpp deleted file mode 100644 index cd50edae7..000000000 --- a/ct_core/include/ct/external/cppad/utility/vector.hpp +++ /dev/null @@ -1,915 +0,0 @@ -// $Id: vector.hpp 3766 2015-12-08 23:12:56Z bradbell $ -# ifndef CPPAD_VECTOR_HPP -# define CPPAD_VECTOR_HPP - -/* -------------------------------------------------------------------------- -CppAD: C++ Algorithmic Differentiation: Copyright (C) 2003-15 Bradley M. Bell - -CppAD is distributed under multiple licenses. This distribution is under -the terms of the - Eclipse Public License Version 1.0. - -A copy of this license is included in the COPYING file of this distribution. -Please visit http://www.coin-or.org/CppAD/ for information on other licenses. --------------------------------------------------------------------------- */ - -/* -$begin CppAD_vector$$ -$spell - rvalues - thread_alloc - cppad.hpp - Bool - resize - cout - endl - std - Cpp - const - vec - ostream - elem -$$ - - -$section The CppAD::vector Template Class$$ -$mindex vector CppAD [] push thread_alloc$$ - -$head Syntax$$ -$code%# include $$ - -$head Description$$ -The include file $code cppad/vector.hpp$$ defines the -vector template class $code CppAD::vector$$. -This is a $cref SimpleVector$$ template class and in addition -it has the features listed below: - -$head Include$$ -The file $code cppad/vector.hpp$$ is included by $code cppad/cppad.hpp$$ -but it can also be included separately with out the rest of the -CppAD include files. - -$head capacity$$ -If $icode x$$ is a $codei%CppAD::vector<%Scalar%>%$$, -and $icode cap$$ is a $code size_t$$ object, -$codei% - %cap% = %x%.capacity() -%$$ -set $icode cap$$ to the number of $icode Scalar$$ objects that -could fit in the memory currently allocated for $icode x$$. -Note that -$codei% - %x%.size() <= %x%.capacity() -%$$ - -$head Assignment$$ -If $icode x$$ and $icode y$$ are -$codei%CppAD::vector<%Scalar%>%$$ objects, -$codei% - %y% = %x% -%$$ -has all the properties listed for a -$cref/simple vector assignment/SimpleVector/Assignment/$$ -plus the following: - -$subhead Check Size$$ -The $code CppAD::vector$$ template class will check that -the size of $icode x$$ is either zero or the size of $icode y$$ -before doing the assignment. -If this is not the case, $code CppAD::vector$$ will use -$cref ErrorHandler$$ -to generate an appropriate error report. -Allowing for assignment to a vector with size zero makes the following -code work: -$codei% - CppAD::vector<%Scalar%> %y%; - %y% = %x%; -%$$ - -$subhead Return Reference$$ -A reference to the vector $icode y$$ is returned. -An example use of this reference is in multiple assignments of the form -$codei% - %z% = %y% = %x% -%$$ - -$subhead Move Semantics$$ -If the C++ compiler supports move semantic rvalues using the $code &&$$ -syntax, then it will be used during the vector assignment statement. -This means that return values and other temporaries are not be copied, -but rather pointers are transferred. - -$head Element Access$$ -If $icode x$$ is a $codei%CppAD::vector<%Scalar%>%$$ object -and $code i$$ has type $code size_t$$, -$codei% - %x%[%i%] -%$$ -has all the properties listed for a -$cref/simple vector element access/SimpleVector/Element Access/$$ -plus the following: -$pre - -$$ -The object $icode%x%[%i%]%$$ has type $icode Scalar$$ -(is not possibly a different type that can be converted to $icode Scalar$$). -$pre - -$$ -If $icode i$$ is not less than the size of the $icode x$$, -$code CppAD::vector$$ will use -$cref ErrorHandler$$ -to generate an appropriate error report. - -$head push_back$$ -If $icode x$$ is a $codei%CppAD::vector<%Scalar%>%$$ object -with size equal to $icode n$$ and -$icode s$$ has type $icode Scalar$$, -$codei% - %x%.push_back(%s%) -%$$ -extends the vector $icode x$$ so that its new size is $icode n$$ plus one -and $icode%x%[%n%]%$$ is equal to $icode s$$ -(equal in the sense of the $icode Scalar$$ assignment operator). - -$head push_vector$$ -If $icode x$$ is a $codei%CppAD::vector<%Scalar%>%$$ object -with size equal to $icode n$$ and -$icode v$$ is a $cref/simple vector/SimpleVector/$$ -with elements of type $icode Scalar$$ and size $icode m$$, -$codei% - %x%.push_vector(%v%) -%$$ -extends the vector $icode x$$ so that its new size is $icode%n%+%m%$$ -and $icode%x%[%n% + %i%]%$$ is equal to $icode%v%[%i%]%$$ -for $icode%i = 1 , ... , m-1%$$ -(equal in the sense of the $icode Scalar$$ assignment operator). - -$head Output$$ -If $icode x$$ is a $codei%CppAD::vector<%Scalar%>%$$ object -and $icode os$$ is an $code std::ostream$$, -and the operation -$codei% - %os% << %x% -%$$ -will output the vector $icode x$$ to the standard -output stream $icode os$$. -The elements of $icode x$$ are enclosed at the beginning by a -$code {$$ character, -they are separated by $code ,$$ characters, -and they are enclosed at the end by $code }$$ character. -It is assumed by this operation that if $icode e$$ -is an object with type $icode Scalar$$, -$codei% - %os% << %e% -%$$ -will output the value $icode e$$ to the standard -output stream $icode os$$. - -$head resize$$ -The call $icode%x%.resize(%n%)%$$ set the size of $icode x$$ equal to -$icode n$$. -If $icode%n% <= %x%.capacity()%$$, -no memory is freed or allocated, the capacity of $icode x$$ does not change, -and the data in $icode x$$ is preserved. -If $icode%n% > %x%.capacity()%$$, -new memory is allocated and the data in $icode x$$ is lost -(not copied to the new memory location). - -$head clear$$ -All memory allocated for the vector is freed -and both its size and capacity are set to zero. -The can be useful when using very large vectors -and when checking for memory leaks (and there are global vectors) -see the $cref/memory/CppAD_vector/Memory and Parallel Mode/$$ discussion. - -$head data$$ -If $icode x$$ is a $codei%CppAD::vector<%Scalar%>%$$ object -$codei% - %x%.data() -%$$ -returns a pointer to a $icode Scalar$$ object such that for -$codei%0 <= %i% < %x%.size()%$$, -$icode%x%[%i%]%$$ and $icode%x%.data()[%i%]%$$ -are the same $icode Scalar$$ object. -If $icode x$$ is $code const$$, the pointer is $code const$$. -If $icode%x%.capacity()%$$ is zero, the value of the pointer is not defined. -The pointer may no longer be valid after the following operations on -$icode x$$: -its destructor, -$code clear$$, -$code resize$$, -$code push_back$$, -$code push_vector$$, -assignment to another vector when original size of $icode x$$ is zero. - -$head vectorBool$$ -The file $code $$ also defines the class -$code CppAD::vectorBool$$. -This has the same specifications as $code CppAD::vector$$ -with the following exceptions: - -$subhead Memory$$ -The class $code vectorBool$$ conserves on memory -(on the other hand, $code CppAD::vector$$ is expected to be faster -than $code vectorBool$$). - -$subhead bit_per_unit$$ -The static function call -$codei% - %s% = vectorBool::bit_per_unit() -%$$ -returns the $code size_t$$ value $icode s$$ -which is equal to the number of boolean values (bits) that are -packed into one operational unit. -For example, a logical $code or$$ -acts on this many boolean values with one operation. - -$subhead data$$ -The $cref/data/CppAD_vector/data/$$ function is not supported by -$code vectorBool$$. - -$subhead Output$$ -The $code CppAD::vectorBool$$ output operator -prints each boolean value as -a $code 0$$ for false, -a $code 1$$ for true, -and does not print any other output; i.e., -the vector is written a long sequence of zeros and ones with no -surrounding $code {$$, $code }$$ and with no separating commas or spaces. - -$subhead Element Type$$ -If $icode x$$ has type $code vectorBool$$ -and $icode i$$ has type $code size_t$$, -the element access value $icode%x%[%i%]%$$ has an unspecified type, -referred to here as $icode elementType$$, that supports the following -operations: - -$list number$$ -$icode elementType$$ can be converted to $code bool$$; e.g. -the following syntax is supported: -$codei% - static_cast( %x%[%i%] ) -%$$ - -$lnext -$icode elementType$$ supports the assignment operator $code =$$ where the -right hand side is a $code bool$$ or an $icode elementType$$ object; e.g., -if $icode y$$ has type $code bool$$, the following syntax is supported: -$codei% - %x%[%i%] = %y% -%$$ - -$lnext -The result of an assignment to an $icode elementType$$ -also has type $icode elementType$$. -Thus, if $icode z$$ has type $code bool$$, the following syntax is supported: -$codei% - %z% = %x%[%i%] = %y% -%$$ -$lend - -$head Memory and Parallel Mode$$ -These vectors use the multi-threaded fast memory allocator -$cref thread_alloc$$: - -$list number$$ -The routine $cref/parallel_setup/ta_parallel_setup/$$ must -be called before these vectors can be used -$cref/in parallel/ta_in_parallel/$$. -$lnext -Using these vectors affects the amount of memory -$cref/in_use/ta_inuse/$$ and $cref/available/ta_available/$$. -$lnext -Calling $cref/clear/CppAD_vector/clear/$$, -makes the corresponding memory available (though $code thread_alloc$$) -to the current thread. -$lnext -Available memory -can then be completely freed using $cref/free_available/ta_free_available/$$. -$lend - -$head Example$$ -$children% - example/cppad_vector.cpp% - example/vector_bool.cpp -%$$ -The files -$cref cppad_vector.cpp$$ and -$cref vector_bool.cpp$$ each -contain an example and test of this template class. -They return true if they succeed and false otherwise. - -$head Exercise$$ -Create and run a program that contains the following code: -$codep - CppAD::vector x(3); - size_t i; - for(i = 0; i < 3; i++) - x[i] = 4. - i; - std::cout << "x = " << x << std::endl; -$$ - -$end - - -$end - ------------------------------------------------------------------------- -*/ - -# include -# include -# include -# include -# include -# include - -namespace CppAD { // BEGIN_CPPAD_NAMESPACE -/*! -\file vector.hpp -File used to define CppAD::vector and CppAD::vectorBool -*/ - -// --------------------------------------------------------------------------- -/*! -The CppAD Simple Vector template class. -*/ -template -class vector { -private: - /// maximum number of Type elements current allocation can hold - size_t capacity_; - /// number of Type elements currently in this vector - size_t length_; - /// pointer to the first type elements - /// (not defined and should not be used when capacity_ = 0) - Type* data_; - /// delete data pointer - void delete_data(Type* data_ptr) - { thread_alloc::delete_array(data_ptr); } -public: - /// type of the elements in the vector - typedef Type value_type; - - /// default constructor sets capacity_ = length_ = data_ = 0 - inline vector(void) - : capacity_(0), length_(0), data_(CPPAD_NULL) - { } - /// sizing constructor - inline vector( - /// number of elements in this vector - size_t n - ) : capacity_(0), length_(0), data_(CPPAD_NULL) - { resize(n); } - - /// copy constructor - inline vector( - /// the *this vector will be a copy of \c x - const vector& x - ) : capacity_(0), length_(0), data_(CPPAD_NULL) - { resize(x.length_); - - // copy the data - for(size_t i = 0; i < length_; i++) - data_[i] = x.data_[i]; - } - /// destructor - ~vector(void) - { if( capacity_ > 0 ) - delete_data(data_); - } - - /// maximum number of elements current allocation can store - inline size_t capacity(void) const - { return capacity_; } - - /// number of elements currently in this vector. - inline size_t size(void) const - { return length_; } - - /// raw pointer to the data - inline Type* data(void) - { return data_; } - - /// const raw pointer to the data - inline const Type* data(void) const - { return data_; } - - /// change the number of elements in this vector. - inline void resize( - /// new number of elements for this vector - size_t n - ) - { length_ = n; - - // check if we can use current memory - if( capacity_ >= length_ ) - return; - - // check if there is old memory to be freed - if( capacity_ > 0 ) - delete_data(data_); - - // get new memory and set capacity - data_ = thread_alloc::create_array(length_, capacity_); - } - - /// free memory and set number of elements to zero - inline void clear(void) - { length_ = 0; - // check if there is old memory to be freed - if( capacity_ > 0 ) - delete_data(data_); - capacity_ = 0; - } - - /// vector assignment operator - inline vector& operator=( - /// right hand size of the assingment operation - const vector& x - ) - { size_t i; - // If original lenght is zero, then resize it. - // Otherwise a length mismatch is an error. - if( length_ == 0 ) - resize( x.length_ ); - CPPAD_ASSERT_KNOWN( - length_ == x.length_ , - "vector: size miss match in assignment operation" - ); - for(i = 0; i < length_; i++) - data_[i] = x.data_[i]; - return *this; - } -# if CPPAD_USE_CPLUSPLUS_2011 - /// vector assignment operator with move semantics - inline vector& operator=( - /// right hand size of the assingment operation - vector&& x - ) - { CPPAD_ASSERT_KNOWN( - length_ == x.length_ || (length_ == 0), - "vector: size miss match in assignment operation" - ); - if( this != &x ) - { clear(); - // - length_ = x.length_; - capacity_ = x.capacity_; - data_ = x.data_; - // - x.length_ = 0; - x.capacity_ = 0; - x.data_ = CPPAD_NULL; - } - return *this; - } -# endif - /// non-constant element access; i.e., we can change this element value - Type& operator[]( - /// element index, must be less than length - size_t i - ) - { CPPAD_ASSERT_KNOWN( - i < length_, - "vector: index greater than or equal vector size" - ); - return data_[i]; - } - /// constant element access; i.e., we cannot change this element value - const Type& operator[]( - /// element index, must be less than length - size_t i - ) const - { CPPAD_ASSERT_KNOWN( - i < length_, - "vector: index greater than or equal vector size" - ); - return data_[i]; - } - /// add an element to the back of this vector - void push_back( - /// value of the element - const Type& s - ) - { // case where no allocation is necessary - if( length_ + 1 <= capacity_ ) - { data_[length_++] = s; - return; - } - CPPAD_ASSERT_UNKNOWN( length_ == capacity_ ); - - // store old length, capacity and data - size_t old_length = length_; - size_t old_capacity = capacity_; - Type* old_data = data_; - - // set the new length, capacity and data - length_ = 0; - capacity_ = 0; - resize(old_length + 1); - - // copy old data values - for(size_t i = 0; i < old_length; i++) - data_[i] = old_data[i]; - - // put the new element in the vector - CPPAD_ASSERT_UNKNOWN( old_length + 1 <= capacity_ ); - data_[old_length] = s; - - // free old data - if( old_capacity > 0 ) - delete_data(old_data); - - CPPAD_ASSERT_UNKNOWN( old_length + 1 == length_ ); - CPPAD_ASSERT_UNKNOWN( length_ <= capacity_ ); - } - - /*! add vector to the back of this vector - (we could not use push_back becasue MS V++ 7.1 did not resolve - to non-template member function when scalar is used.) - */ - template - void push_vector( - /// value of the vector that we are adding - const Vector& v - ) - { CheckSimpleVector(); - size_t m = v.size(); - - // case where no allcoation is necessary - if( length_ + m <= capacity_ ) - { for(size_t i = 0; i < m; i++) - data_[length_++] = v[i]; - return; - } - - // store old length, capacity and data - size_t old_length = length_; - size_t old_capacity = capacity_; - Type* old_data = data_; - - // set new length, capacity and data - length_ = 0; - capacity_ = 0; - resize(old_length + m); - - // copy old data values - for(size_t i = 0; i < old_length; i++) - data_[i] = old_data[i]; - - // put the new elements in the vector - CPPAD_ASSERT_UNKNOWN( old_length + m <= capacity_ ); - for(size_t i = 0; i < m; i++) - data_[old_length + i] = v[i]; - - // free old data - if( old_capacity > 0 ) - delete_data(old_data); - - CPPAD_ASSERT_UNKNOWN( old_length + m == length_ ); - CPPAD_ASSERT_UNKNOWN( length_ <= capacity_ ); - } -}; - -/// output a vector -template -inline std::ostream& operator << ( - /// stream to write the vector to - std::ostream& os , - /// vector that is output - const CppAD::vector& vec ) -{ size_t i = 0; - size_t n = vec.size(); - - os << "{ "; - while(i < n) - { os << vec[i++]; - if( i < n ) - os << ", "; - } - os << " }"; - return os; -} - -// --------------------------------------------------------------------------- -/*! -Class that is used to hold a non-constant element of a vector. -*/ -class vectorBoolElement { - /// the boolean data is packed with sizeof(UnitType) bits per value - typedef size_t UnitType; -private: - /// pointer to the UnitType value holding this eleemnt - UnitType* unit_; - /// mask for the bit corresponding to this element - /// (all zero except for bit that corresponds to this element) - UnitType mask_; -public: - /// constructor from member values - vectorBoolElement( - /// unit for this element - UnitType* unit , - /// mask for this element - UnitType mask ) - : unit_(unit) , mask_(mask) - { } - /// constuctor from another element - vectorBoolElement( - /// other element - const vectorBoolElement& e ) - : unit_(e.unit_) , mask_(e.mask_) - { } - /// conversion to a boolean value - operator bool() const - { return (*unit_ & mask_) != 0; } - /// assignment of this element to a bool - vectorBoolElement& operator=( - /// right hand side for assignment - bool bit - ) - { if(bit) - *unit_ |= mask_; - else *unit_ &= ~mask_; - return *this; - } - /// assignment of this element to another element - vectorBoolElement& operator=(const vectorBoolElement& e) - { if( *(e.unit_) & e.mask_ ) - *unit_ |= mask_; - else *unit_ &= ~mask_; - return *this; - } -}; - -class vectorBool { - /// the boolean data is packed with sizeof(UnitType) bits per value - typedef size_t UnitType; -private: - /// number of bits packed into each UnitType value in data_ - static const size_t bit_per_unit_ - = std::numeric_limits::digits; - /// number of UnitType values in data_ - size_t n_unit_; - /// number of bits currently stored in this vector - size_t length_; - /// pointer to where the bits are stored - UnitType *data_; - - /// minimum number of UnitType values that can store length_ bits - /// (note that this is really a function of length_) - size_t unit_min(void) - { if( length_ == 0 ) - return 0; - return (length_ - 1) / bit_per_unit_ + 1; - } -public: - /// type corresponding to the elements of this vector - /// (note that non-const elements actually use vectorBoolElement) - typedef bool value_type; - - // static member function - static size_t bit_per_unit(void) - { return bit_per_unit_; } - - /// default constructor (sets all member data to zero) - inline vectorBool(void) : n_unit_(0), length_(0), data_(CPPAD_NULL) - { } - /// sizing constructor - inline vectorBool( - /// number of bits in this vector - size_t n - ) : n_unit_(0), length_(n), data_(CPPAD_NULL) - { if( length_ > 0 ) - { // set n_unit and data - size_t min_unit = unit_min(); - data_ = thread_alloc::create_array(min_unit, n_unit_); - } - } - /// copy constructor - inline vectorBool( - /// the *this vector will be a copy of \c v - const vectorBool& v - ) : n_unit_(0), length_(v.length_), data_(CPPAD_NULL) - { if( length_ > 0 ) - { // set n_unit and data - size_t min_unit = unit_min(); - data_ = thread_alloc::create_array(min_unit, n_unit_); - - // copy values using UnitType assignment operator - CPPAD_ASSERT_UNKNOWN( min_unit <= v.n_unit_ ); - size_t i; - for(i = 0; i < min_unit; i++) - data_[i] = v.data_[i]; - } - } - /// destructor - ~vectorBool(void) - { if( n_unit_ > 0 ) - thread_alloc::delete_array(data_); - } - - /// number of elements in this vector - inline size_t size(void) const - { return length_; } - - /// maximum number of elements current allocation can store - inline size_t capacity(void) const - { return n_unit_ * bit_per_unit_; } - - /// change number of elements in this vector - inline void resize( - /// new number of elements for this vector - size_t n - ) - { length_ = n; - // check if we can use the current memory - size_t min_unit = unit_min(); - if( n_unit_ >= min_unit ) - return; - // check if there is old memory to be freed - if( n_unit_ > 0 ) - thread_alloc::delete_array(data_); - // get new memory and set n_unit - data_ = thread_alloc::create_array(min_unit, n_unit_); - } - - /// free memory and set number of elements to zero - inline void clear(void) - { length_ = 0; - // check if there is old memory to be freed - if( n_unit_ > 0 ) - thread_alloc::delete_array(data_); - n_unit_ = 0; - } - - /// vector assignment operator - inline vectorBool& operator=( - /// right hand size of the assingment operation - const vectorBool& v - ) - { size_t i; - // If original lenght is zero, then resize it. - // Otherwise a length mismatch is an error. - if( length_ == 0 ) - resize( v.length_ ); - CPPAD_ASSERT_KNOWN( - length_ == v.length_ , - "vectorBool: size miss match in assignment operation" - ); - size_t min_unit = unit_min(); - CPPAD_ASSERT_UNKNOWN( min_unit <= n_unit_ ); - CPPAD_ASSERT_UNKNOWN( min_unit <= v.n_unit_ ); - for(i = 0; i < min_unit; i++) - data_[i] = v.data_[i]; - return *this; - } -# if CPPAD_USE_CPLUSPLUS_2011 - /// vector assignment operator with move semantics - inline vectorBool& operator=( - /// right hand size of the assingment operation - vectorBool&& x - ) - { CPPAD_ASSERT_KNOWN( - length_ == x.length_ || (length_ == 0), - "vectorBool: size miss match in assignment operation" - ); - if( this != &x ) - { clear(); - // - length_ = x.length_; - n_unit_ = x.n_unit_; - data_ = x.data_; - // - x.length_ = 0; - x.n_unit_ = 0; - x.data_ = CPPAD_NULL; - } - return *this; - } -# endif - - - /// non-constant element access; i.e., we can change this element value - vectorBoolElement operator[]( - /// element index, must be less than length - size_t k - ) - { size_t i, j; - CPPAD_ASSERT_KNOWN( - k < length_, - "vectorBool: index greater than or equal vector size" - ); - i = k / bit_per_unit_; - j = k - i * bit_per_unit_; - return vectorBoolElement(data_ + i , UnitType(1) << j ); - } - /// constant element access; i.e., we cannot change this element value - bool operator[](size_t k) const - { size_t i, j; - UnitType unit, mask; - CPPAD_ASSERT_KNOWN( - k < length_, - "vectorBool: index greater than or equal vector size" - ); - i = k / bit_per_unit_; - j = k - i * bit_per_unit_; - unit = data_[i]; - mask = UnitType(1) << j; - return (unit & mask) != 0; - } - /// add an element to the back of this vector - void push_back( - /// value of the element - bool bit - ) - { CPPAD_ASSERT_UNKNOWN( unit_min() <= n_unit_ ); - size_t i, j; - UnitType mask; - if( length_ + 1 > n_unit_ * bit_per_unit_ ) - { CPPAD_ASSERT_UNKNOWN( unit_min() == n_unit_ ); - // store old n_unit and data values - size_t old_n_unit = n_unit_; - UnitType* old_data = data_; - // set new n_unit and data values - data_ = thread_alloc::create_array(n_unit_+1, n_unit_); - // copy old data values - for(i = 0; i < old_n_unit; i++) - data_[i] = old_data[i]; - // free old data - if( old_n_unit > 0 ) - thread_alloc::delete_array(old_data); - } - i = length_ / bit_per_unit_; - j = length_ - i * bit_per_unit_; - mask = UnitType(1) << j; - if( bit ) - data_[i] |= mask; - else data_[i] &= ~mask; - length_++; - } - /// add vector to the back of this vector - template - void push_vector( - /// value of the vector that we are adding - const Vector& v - ) - { CheckSimpleVector(); - size_t min_unit = unit_min(); - CPPAD_ASSERT_UNKNOWN( length_ <= n_unit_ * bit_per_unit_ ); - // some temporaries - size_t i, j, k, ell; - UnitType mask; - bool bit; - // store old length - size_t old_length = length_; - // new length and minium number of units; - length_ = length_ + v.size(); - min_unit = unit_min(); - if( length_ >= n_unit_ * bit_per_unit_ ) - { // store old n_unit and data value - size_t old_n_unit = n_unit_; - UnitType* old_data = data_; - // set new n_unit and data values - data_ = thread_alloc::create_array(min_unit, n_unit_); - // copy old data values - for(i = 0; i < old_n_unit; i++) - data_[i] = old_data[i]; - // free old data - if( old_n_unit > 0 ) - thread_alloc::delete_array(old_data); - } - ell = old_length; - for(k = 0; k < v.size(); k++) - { - i = ell / bit_per_unit_; - j = ell - i * bit_per_unit_; - bit = v[k]; - mask = UnitType(1) << j; - if( bit ) - data_[i] |= mask; - else data_[i] &= ~mask; - ell++; - } - CPPAD_ASSERT_UNKNOWN( length_ == ell ); - CPPAD_ASSERT_UNKNOWN( length_ <= n_unit_ * bit_per_unit_ ); - } -}; - -/// output a vector -inline std::ostream& operator << ( - /// steam to write the vector to - std::ostream& os , - /// vector that is output - const vectorBool& v ) -{ size_t i = 0; - size_t n = v.size(); - - while(i < n) - os << v[i++]; - return os; -} - -} // END_CPPAD_NAMESPACE -# endif diff --git a/ct_core/package.xml b/ct_core/package.xml index 243f09b54..d9b91c447 100755 --- a/ct_core/package.xml +++ b/ct_core/package.xml @@ -1,6 +1,6 @@ ct_core - 3.0.1 + 3.0.2 Control toolbox - core module. diff --git a/ct_core/test/CMakeLists.txt b/ct_core/test/CMakeLists.txt index e2e645870..95743847e 100644 --- a/ct_core/test/CMakeLists.txt +++ b/ct_core/test/CMakeLists.txt @@ -20,12 +20,17 @@ package_add_test(InterpolationTest InterpolationTest.cpp) package_add_test(DiscreteArrayTest DiscreteArrayTest.cpp) package_add_test(DiscreteTrajectoryTest DiscreteTrajectoryTest.cpp) package_add_test(LinspaceTest LinspaceTest.cpp) -package_add_test(AutoDiffLinearizerTest AutoDiffLinearizerTest.cpp) package_add_test(SwitchingTest switching/SwitchingTest.cpp) package_add_test(SwitchedControlledSystemTest switching/SwitchedControlledSystemTest.cpp) package_add_test(SwitchedDiscreteControlledSystemTest switching/SwitchedDiscreteControlledSystemTest.cpp) package_add_test(MatrixInversionTest math/MatrixInversionTest.cpp) -package_add_test(CodegenTests CodegenTests.cpp) +if(CPPAD) + package_add_test(AutoDiffLinearizerTest AutoDiffLinearizerTest.cpp) +endif() +if(CPPADCG AND LLVM) + package_add_test(CodegenTests CodegenTests.cpp) +endif() + ## unit tests for prespec libraries if(USE_PRESPEC) package_add_test(IntegrationTestPrespec integration/IntegrationTestPrespec.cpp) diff --git a/ct_core/test/math/JacobianCGTest.h b/ct_core/test/math/JacobianCGTest.h index 9a7495462..a46bdc172 100644 --- a/ct_core/test/math/JacobianCGTest.h +++ b/ct_core/test/math/JacobianCGTest.h @@ -16,6 +16,7 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) // define the input and output sizes of the function const size_t inDim = 3; //!< dimension of x const size_t outDim = 2; //!< dimension of y +const bool verbose = false; //! the Jacobian codegen class typedef DerivativesCppadJIT derivativesCppadJIT; @@ -67,119 +68,154 @@ Eigen::Matrix hessianCheck(const Eigen::Matrix; - typename derivativesCppad::FUN_TYPE_AD f_ad = testFunction; + // create a function handle (also works for class methods, lambdas, function pointers, ...) + typename derivativesCppadJIT::FUN_TYPE_CG f_cg = testFunction; + typename derivativesCppad::FUN_TYPE_AD f_ad = testFunction; - // initialize the Auto-Diff Codegen Jacobian - derivativesCppadJIT jacCG(f_cg); - derivativesCppad jacAd(f_ad); + // initialize the Auto-Diff Codegen Jacobian + derivativesCppadJIT jacCG(f_cg); + derivativesCppad jacAd(f_ad); - DerivativesCppadSettings settings; - settings.createForwardZero_ = true; - settings.createJacobian_ = true; + DerivativesCppadSettings settings; + settings.createForwardZero_ = true; + settings.createJacobian_ = true; + settings.useDynamicLibrary_ = useDynamicLib; - // create a random double vector - Eigen::VectorXd someVec(inDim); - someVec.setRandom(); + // create a random double vector + Eigen::VectorXd someVec(inDim); + someVec.setRandom(); - // test evaluation of forward zero before compilation - Eigen::VectorXd vecOut = jacAd.forwardZero(someVec); + // test evaluation of forward zero before compilation + Eigen::VectorXd vecOut = jacAd.forwardZero(someVec); - // compile the Jacobian - jacCG.compileJIT(settings, "forwardZeroTestLib"); + // compile the Jacobian + jacCG.compileJIT(settings, "forwardZeroTestLib", verbose); - // test evaluation of forward zero after compilation - Eigen::VectorXd vecOut2 = jacCG.forwardZero(someVec); + // test evaluation of forward zero after compilation + Eigen::VectorXd vecOut2 = jacCG.forwardZero(someVec); - // verify the outputs - ASSERT_LT((vecOut - vecOut2).array().abs().maxCoeff(), 1e-10); + // verify the outputs + ASSERT_LT((vecOut - vecOut2).array().abs().maxCoeff(), 1e-10); +} - } catch (std::exception& e) + +void executeJITCompilationTest(bool useDynamicLib) +{ + // create a function handle (also works for class methods, lambdas, function pointers, ...) + typename derivativesCppadJIT::FUN_TYPE_CG f = testFunction; + typename derivativesCppad::FUN_TYPE_AD f_ad = testFunction; + + // initialize the Auto-Diff Codegen Jacobian + derivativesCppadJIT jacCG(f); + derivativesCppad jacAd(f_ad); + + DerivativesCppadSettings settings; + settings.createJacobian_ = true; + settings.useDynamicLibrary_ = useDynamicLib; + + // compile the Jacobian + jacCG.compileJIT(settings, "jacobianCGLib", verbose); + + // create an input vector + Eigen::Matrix x; + + for (size_t i = 0; i < 1000; i++) { - std::cout << "Exception thrown: " << e.what() << std::endl; - ASSERT_TRUE(false); + // create a random input + x.setRandom(); + + // verify agains the analytical Jacobian + ASSERT_LT((jacCG.jacobian(x) - jacobianCheck(x)).array().abs().maxCoeff(), 1e-10); + ASSERT_LT((jacAd.jacobian(x) - jacobianCheck(x)).array().abs().maxCoeff(), 1e-10); + ASSERT_LT((jacCG.jacobian(x) - jacAd.jacobian(x)).array().abs().maxCoeff(), 1e-10); } } -/*! - * Test for just-in-time compilation of the Jacobian and subsequent evaluation of it - */ -TEST(JacobianCGTest, JITCompilationTest) +void executeJitHessianTest(bool useDynamicLib) { - try - { - // create a function handle (also works for class methods, lambdas, function pointers, ...) - typename derivativesCppadJIT::FUN_TYPE_CG f = testFunction; - typename derivativesCppad::FUN_TYPE_AD f_ad = testFunction; + typename derivativesCppadJIT::FUN_TYPE_CG f = testFunction; + typename derivativesCppad::FUN_TYPE_AD f_ad = testFunction; - // initialize the Auto-Diff Codegen Jacobian - derivativesCppadJIT jacCG(f); - derivativesCppad jacAd(f_ad); + derivativesCppadJIT hessianCg(f); + derivativesCppad hessianAd(f_ad); - DerivativesCppadSettings settings; - settings.createJacobian_ = true; + DerivativesCppadSettings settings; + settings.createHessian_ = true; + settings.useDynamicLibrary_ = useDynamicLib; - // compile the Jacobian - jacCG.compileJIT(settings, "jacobianCGLib"); + hessianCg.compileJIT(settings, "hessianCGLib", verbose); - // create an input vector - Eigen::Matrix x; + Eigen::Matrix x; + Eigen::Matrix w; - for (size_t i = 0; i < 1000; i++) - { - // create a random input - x.setRandom(); - - // verify agains the analytical Jacobian - ASSERT_LT((jacCG.jacobian(x) - jacobianCheck(x)).array().abs().maxCoeff(), 1e-10); - ASSERT_LT((jacAd.jacobian(x) - jacobianCheck(x)).array().abs().maxCoeff(), 1e-10); - ASSERT_LT((jacCG.jacobian(x) - jacAd.jacobian(x)).array().abs().maxCoeff(), 1e-10); - } - } catch (std::exception& e) + for (size_t i = 0; i < 1000; ++i) { - std::cout << "Exception thrown: " << e.what() << std::endl; - ASSERT_TRUE(false); + x.setRandom(); + w.setRandom(); + + ASSERT_LT((hessianCg.hessian(x, w) - hessianCheck(x, w)).array().abs().maxCoeff(), 1e-10); + ASSERT_LT((hessianAd.hessian(x, w) - hessianCheck(x, w)).array().abs().maxCoeff(), 1e-10); + ASSERT_LT((hessianCg.hessian(x, w) - hessianAd.hessian(x, w)).array().abs().maxCoeff(), 1e-10); } } -TEST(HessianCGTest, JITHessianTest) +void executeJITCloneTest(bool useDynamicLib) { - try - { - typename derivativesCppadJIT::FUN_TYPE_CG f = testFunction; - typename derivativesCppad::FUN_TYPE_AD f_ad = testFunction; + typename derivativesCppadJIT::FUN_TYPE_CG f = testFunction; + typename derivativesCppad::FUN_TYPE_AD f_ad = testFunction; + + // initialize the Auto-Diff Codegen Jacobian + std::shared_ptr jacCG(new derivativesCppadJIT(f)); + std::shared_ptr jacAd(new derivativesCppad(f_ad)); - derivativesCppadJIT hessianCg(f); - derivativesCppad hessianAd(f_ad); + DerivativesCppadSettings settings; + settings.createJacobian_ = true; + settings.useDynamicLibrary_ = useDynamicLib; - DerivativesCppadSettings settings; - settings.createHessian_ = true; + // compile the Jacobian + jacCG->compileJIT(settings, "jacobianCGLib", verbose); - hessianCg.compileJIT(settings, "hessianCGLib"); + // create an input vector + Eigen::Matrix x; - Eigen::Matrix x; - Eigen::Matrix w; + std::shared_ptr jacCG_cloned(jacCG->clone()); - for (size_t i = 0; i < 1000; ++i) - { - x.setRandom(); - w.setRandom(); + // make sure the underlying dynamic libraries are not identical + if (useDynamicLib && (jacCG_cloned->getDynamicLib() == jacCG->getDynamicLib())) + { + std::cout << "FATAL ERROR: dynamic library not cloned correctly in JIT." << std::endl; + ASSERT_TRUE(false); + } + if (!useDynamicLib && (jacCG_cloned->getLlvmLib() == jacCG->getLlvmLib())) + { + std::cout << "FATAL ERROR: Llvm library not cloned correctly in JIT." << std::endl; + ASSERT_TRUE(false); + } - ASSERT_LT((hessianCg.hessian(x, w) - hessianCheck(x, w)).array().abs().maxCoeff(), 1e-10); - ASSERT_LT((hessianAd.hessian(x, w) - hessianCheck(x, w)).array().abs().maxCoeff(), 1e-10); - ASSERT_LT((hessianCg.hessian(x, w) - hessianAd.hessian(x, w)).array().abs().maxCoeff(), 1e-10); - } + for (size_t i = 0; i < 100; i++) + { + // create a random input + x.setRandom(); + // verify agains the analytical Jacobian + ASSERT_LT((jacCG_cloned->jacobian(x) - jacobianCheck(x)).array().abs().maxCoeff(), 1e-10); + ASSERT_LT((jacCG_cloned->jacobian(x) - jacAd->jacobian(x)).array().abs().maxCoeff(), 1e-10); + } +} + +/*! + * Test evaluation of the forward-zero function, which should be possible to evaluate in both uncompiled and compiled state + */ +TEST(JacobianCGTest, ForwardZeroTest) +{ + try + { + executeForwardZeroTest(false); //using llvm jit + executeForwardZeroTest(true); // using dynamic library } catch (std::exception& e) { @@ -188,48 +224,59 @@ TEST(HessianCGTest, JITHessianTest) } } - /*! - * Test cloning of JIT compiled libraries + * Test for just-in-time compilation of the Jacobian and subsequent evaluation of it */ -TEST(JacobianCGTest, JITCloneTest) +TEST(JacobianCGTest, JITCompilationTest) { try { - typename derivativesCppadJIT::FUN_TYPE_CG f = testFunction; - typename derivativesCppad::FUN_TYPE_AD f_ad = testFunction; - - // initialize the Auto-Diff Codegen Jacobian - std::shared_ptr jacCG(new derivativesCppadJIT(f)); - std::shared_ptr jacAd(new derivativesCppad(f_ad)); - - DerivativesCppadSettings settings; - settings.createJacobian_ = true; + executeJITCompilationTest(true); + executeJITCompilationTest(false); - // compile the Jacobian - jacCG->compileJIT(settings, "jacobianCGLib"); - - // create an input vector - Eigen::Matrix x; - - std::shared_ptr jacCG_cloned(jacCG->clone()); + } catch (std::exception& e) + { + std::cout << "Exception thrown: " << e.what() << std::endl; + ASSERT_TRUE(false); + } +} - // make sure the underlying dynamic libraries are not identical (dynamic library cloned correctly) - if (jacCG_cloned->getDynamicLib() == jacCG->getDynamicLib()) - { - std::cout << "FATAL ERROR: dynamic library not cloned correctly in JIT." << std::endl; - ASSERT_TRUE(false); - } +TEST(HessianCGTest, JITHessianTest) +{ + try + { + executeJitHessianTest(true); + executeJitHessianTest(false); + } catch (std::exception& e) + { + std::cout << "Exception thrown: " << e.what() << std::endl; + ASSERT_TRUE(false); + } +} - for (size_t i = 0; i < 100; i++) - { - // create a random input - x.setRandom(); +/*! + * Test cloning of JIT compiled libraries + */ +TEST(JacobianCGTest, DISABLED_LlvmCloneTest) +{ + try + { + executeJITCloneTest(false); // Jit using llvm in-memory library + } catch (std::exception& e) + { + std::cout << "Exception thrown: " << e.what() << std::endl; + ASSERT_TRUE(false); + } +} - // verify agains the analytical Jacobian - ASSERT_LT((jacCG_cloned->jacobian(x) - jacobianCheck(x)).array().abs().maxCoeff(), 1e-10); - ASSERT_LT((jacCG_cloned->jacobian(x) - jacAd->jacobian(x)).array().abs().maxCoeff(), 1e-10); - } +/*! + * Test cloning of JIT compiled libraries + */ +TEST(JacobianCGTest, JitCloneTest) +{ + try + { + executeJITCloneTest(true); // Jit using dynamic library } catch (std::exception& e) { std::cout << "Exception thrown: " << e.what() << std::endl; diff --git a/ct_core/test/system/TestSymplecticSystem.h b/ct_core/test/system/TestSymplecticSystem.h index 539a1691f..85395a4d1 100644 --- a/ct_core/test/system/TestSymplecticSystem.h +++ b/ct_core/test/system/TestSymplecticSystem.h @@ -20,6 +20,8 @@ template class TestSymplecticSystem : public SymplecticSystem<1, 1, 1, SCALAR> { public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + static const size_t STATE_DIM = 2; static const size_t CONTROL_DIM = 1; static const size_t POS_DIM = 1; @@ -34,13 +36,16 @@ class TestSymplecticSystem : public SymplecticSystem<1, 1, 1, SCALAR> } TestSymplecticSystem(const TestSymplecticSystem& arg) : SymplecticSystem<1, 1, 1, SCALAR>(arg), w_n_(arg.w_n_) {} - virtual ~TestSymplecticSystem() {} + + virtual ~TestSymplecticSystem() = default; + TestSymplecticSystem* clone() const override { return new TestSymplecticSystem(*this); } + //! need to override this method for a symplectic system virtual void computePdot(const StateVector& x, const StateVector& v, const ControlVector& control, - StateVector& pDot) + StateVector& pDot) override { pDot(0) = v(0); } @@ -49,7 +54,7 @@ class TestSymplecticSystem : public SymplecticSystem<1, 1, 1, SCALAR> virtual void computeVdot(const StateVector& x, const StateVector& p, const ControlVector& control, - StateVector& vDot) + StateVector& vDot) override { vDot(0) = control(0) - w_n_ * w_n_ * p(0); } diff --git a/ct_doc/CMakeLists.txt b/ct_doc/CMakeLists.txt index 17f3694e3..db115f7ad 100755 --- a/ct_doc/CMakeLists.txt +++ b/ct_doc/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required (VERSION 3.3) -project (ct_doc VERSION 3.0.1 ) +project (ct_doc VERSION 3.0.2 ) set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake) diff --git a/ct_doc/doc/changelog.dox b/ct_doc/doc/changelog.dox index 20a787740..4805a9219 100644 --- a/ct_doc/doc/changelog.dox +++ b/ct_doc/doc/changelog.dox @@ -5,7 +5,14 @@ For a complete list of changes, we encourage you to check out our git repository at https://github.com/ethz-adrl/control-toolbox -\section cl_v301 Version 3.0.1 +\section cl_v302 Version 3.0.2 +- upgraded HPIPM to version 0.1.1, which simplified the interface for getting Riccati-matrices from the solver +- resolved ordering-bug for box-constraints +- switched back to differential formulation of LQ problems to maintain comparability with other solutions +- simplified user-interface to the 7 different iLQR-style solver variants +- removed copied code from external repos (CppAD and CppADCodeGen) and provided install script instead + +\section cl_v301 Version 3.0.2 - enabled compatibility with pure cmake (no catkin or ROS required anymore) - fixed bug in explicit template prespecification - fixed bug in exporting dependencies on external solvers diff --git a/ct_doc/doc/ct_doc.doxyfile b/ct_doc/doc/ct_doc.doxyfile index e8581f88d..8f854a036 100644 --- a/ct_doc/doc/ct_doc.doxyfile +++ b/ct_doc/doc/ct_doc.doxyfile @@ -38,13 +38,13 @@ PROJECT_NAME = " " # could be handy for archiving the generated documentation or if some version # control system is used. -PROJECT_NUMBER = 3.0.1 +PROJECT_NUMBER = 3.0.2 # Using the PROJECT_BRIEF tag one can provide an optional one line description # for a project that appears at the top of each page and should give viewer a # quick idea about the purpose of the project. Keep the description short. -PROJECT_BRIEF = " - 3.0.1 Documentation" +PROJECT_BRIEF = " - 3.0.2 Documentation" # With the PROJECT_LOGO tag one can specify an logo or icon that is included in # the documentation. The maximum height of the logo should not exceed 55 pixels diff --git a/ct_doc/doc/installation.dox b/ct_doc/doc/installation.dox index 47a2ed38f..6cc4ea673 100644 --- a/ct_doc/doc/installation.dox +++ b/ct_doc/doc/installation.dox @@ -131,9 +131,9 @@ The following dependencies and bindings are optional but can help to enhance the - IPOPT or SNOPT (for ct::optcon::SnoptSolver and ct::optcon::IpoptSolver as used by ct::optcon::DMS) - - blasfeo linear algebra and HPIPM solver as - alternative high-performance (constrained) linear-quadratic optimal control solver. Check out the *ct-v2* tags. Detailed reference - about blasefeo can be found here. + - blasfeo linear algebra and HPIPM solver as + alternative high-performance (constrained) linear-quadratic optimal control solver. The CT currently supports hpipm version 0.1.1. + Detailed reference about blasefeo can be found here. Both packages were developed by Gianluca Frison, University of Freiburg. - install the catkin_tools build system @@ -168,7 +168,6 @@ Build Flag | Default value | Description -DUSE_INTEL=\ | FALSE | Use Intel compiler instead of the default compiler -DINTEL_CXX_COMPILER=\ | "/opt/intel/bin/icc" | Set Intel C++ compiler binary -DINTEL_C_COMPILER=\ | "/opt/intel/bin/icpc" | Set Intel C compiler binary --DHPIPM=\ | FALSE | Compile with HPIPM support (set $BLASFEO_DIR and $HPIPM_DIR environment variables) */ diff --git a/ct_doc/package.xml b/ct_doc/package.xml index 2a0665201..57cbb4ab8 100755 --- a/ct_doc/package.xml +++ b/ct_doc/package.xml @@ -1,6 +1,6 @@ ct_doc - 3.0.1 + 3.0.2 Control toolbox - Documentation diff --git a/ct_models/CMakeLists.txt b/ct_models/CMakeLists.txt index 0fc953e7f..3f0cd1412 100755 --- a/ct_models/CMakeLists.txt +++ b/ct_models/CMakeLists.txt @@ -3,8 +3,10 @@ cmake_minimum_required (VERSION 3.3) include(${CMAKE_CURRENT_SOURCE_DIR}/../ct/cmake/compilerSettings.cmake) include(${CMAKE_CURRENT_SOURCE_DIR}/../ct/cmake/explicitTemplateHelpers.cmake) include(${CMAKE_CURRENT_SOURCE_DIR}/../ct/cmake/clang-cxx-dev-tools.cmake) +include(${CMAKE_CURRENT_SOURCE_DIR}/../ct/cmake/ct-cmake-helpers.cmake) -project(ct_models VERSION 3.0.1 LANGUAGES CXX) + +project(ct_models VERSION 3.0.2 LANGUAGES CXX) set(CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/cmake") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wfatal-errors -std=c++14 -Wall -Wno-unknown-pragmas") @@ -13,6 +15,11 @@ set(CMAKE_EXPORT_COMPILE_COMMANDS TRUE) find_package(ct_rbd REQUIRED) find_package(Boost REQUIRED system filesystem) +# extract interface compile definitions from previous ct packages as options +importInterfaceCompileDefinitionsAsOptions(ct_core) +importInterfaceCompileDefinitionsAsOptions(ct_optcon) +importInterfaceCompileDefinitionsAsOptions(ct_rbd) + ## define the directories to be included in all ct_rbd targets set(ct_models_target_include_dirs @@ -23,7 +30,7 @@ set(ct_models_target_include_dirs ## define placeholder for ct model libraries -set(CT_MODEL_LIBS "") +set(CT_MODELS_TARGETS "") set(IP_CODEGEN_OUTPUT_DIR "${CMAKE_CURRENT_SOURCE_DIR}/include/ct/models/InvertedPendulum/codegen") set(HYA_CODEGEN_OUTPUT_DIR "${CMAKE_CURRENT_SOURCE_DIR}/include/ct/models/HyA/codegen") @@ -31,9 +38,11 @@ set(HYQ_CODEGEN_OUTPUT_DIR "${CMAKE_CURRENT_SOURCE_DIR}/include/ct/models/HyQ/co configure_file(${CMAKE_CURRENT_SOURCE_DIR}/include/ct/models/CodegenOutputDirs.h.in ${CMAKE_CURRENT_SOURCE_DIR}/include/ct/models/CodegenOutputDirs.h) ################ HyQ ################# -add_executable(HyQLinearizationCodegen src/HyQ/codegen/HyQLinearizationCodegen.cpp) -target_include_directories(HyQLinearizationCodegen PUBLIC ${ct_models_target_include_dirs}) -target_link_libraries(HyQLinearizationCodegen ct_rbd) +if(CPPADCG) + add_executable(HyQLinearizationCodegen src/HyQ/codegen/HyQLinearizationCodegen.cpp) + target_include_directories(HyQLinearizationCodegen PUBLIC ${ct_models_target_include_dirs}) + target_link_libraries(HyQLinearizationCodegen ct_rbd) +endif() if (BUILD_HYQ_FULL) if (NOT USE_CLANG) @@ -41,12 +50,12 @@ if (BUILD_HYQ_FULL) endif() add_library(HyQWithContactModelLinearizedForward include/ct/models/HyQ/codegen/HyQWithContactModelLinearizedForward.cpp) target_link_libraries(HyQWithContactModelLinearizedForward ct_rbd) - list(APPEND CT_MODEL_LIBS HyQWithContactModelLinearizedForward) + list(APPEND CT_MODELS_TARGETS HyQWithContactModelLinearizedForward) ## Forward Dynamics Forward Zero add_library(HyQForwardZero include/ct/models/HyQ/codegen/HyQForwardZero.cpp) target_link_libraries(HyQForwardZero ct_rbd) - list(APPEND CT_MODEL_LIBS HyQForwardZero) + list(APPEND CT_MODELS_TARGETS HyQForwardZero) endif(BUILD_HYQ_FULL) if(BUILD_HYQ_LINEARIZATION_TIMINGS) @@ -57,33 +66,33 @@ if(BUILD_HYQ_LINEARIZATION_TIMINGS) ## Forward Dynamics add_library(HyQWithContactModelLinearizedReverse include/ct/models/HyQ/codegen/HyQWithContactModelLinearizedReverse.cpp) target_link_libraries(HyQWithContactModelLinearizedReverse ct_rbd) - list(APPEND CT_MODEL_LIBS HyQWithContactModelLinearizedReverse) + list(APPEND CT_MODELS_TARGETS HyQWithContactModelLinearizedReverse) add_library(HyQBareModelLinearizedForward include/ct/models/HyQ/codegen/HyQBareModelLinearizedForward.cpp) target_link_libraries(HyQBareModelLinearizedForward ct_rbd ) - list(APPEND CT_MODEL_LIBS HyQBareModelLinearizedForward) + list(APPEND CT_MODELS_TARGETS HyQBareModelLinearizedForward) add_library(HyQBareModelLinearizedReverse include/ct/models/HyQ/codegen/HyQBareModelLinearizedReverse.cpp) target_link_libraries(HyQBareModelLinearizedReverse ct_rbd ) - list(APPEND CT_MODEL_LIBS HyQBareModelLinearizedReverse) + list(APPEND CT_MODELS_TARGETS HyQBareModelLinearizedReverse) ## Inverse Dynamics add_library(HyQJacInverseDynamicsForward include/ct/models/HyQ/codegen/HyQInverseDynJacForward.cpp) target_link_libraries(HyQJacInverseDynamicsForward ct_rbd ) - list(APPEND CT_MODEL_LIBS HyQJacInverseDynamicsForward) + list(APPEND CT_MODELS_TARGETS HyQJacInverseDynamicsForward) add_library(HyQJacInverseDynamicsReverse include/ct/models/HyQ/codegen/HyQInverseDynJacReverse.cpp) target_link_libraries(HyQJacInverseDynamicsReverse ct_rbd ) - list(APPEND CT_MODEL_LIBS HyQJacInverseDynamicsReverse) + list(APPEND CT_MODELS_TARGETS HyQJacInverseDynamicsReverse) ## ForwardKinematics add_library(HyQJacForwardKinForward include/ct/models/HyQ/codegen/HyQForwardKinJacForward.cpp) target_link_libraries(HyQJacForwardKinForward ct_rbd ) - list(APPEND CT_MODEL_LIBS HyQJacForwardKinForward) + list(APPEND CT_MODELS_TARGETS HyQJacForwardKinForward) add_library(HyQJacForwardKinReverse include/ct/models/HyQ/codegen/HyQForwardKinJacReverse.cpp) target_link_libraries(HyQJacForwardKinReverse ct_rbd ) - list(APPEND CT_MODEL_LIBS HyQJacForwardKinReverse) + list(APPEND CT_MODELS_TARGETS HyQJacForwardKinReverse) add_executable(HyQcompareForwardReverseFD src/HyQ/codegen/compareForwardReverseFD.cpp) target_link_libraries(HyQcompareForwardReverseFD @@ -92,61 +101,69 @@ if(BUILD_HYQ_LINEARIZATION_TIMINGS) HyQBareModelLinearizedForward HyQBareModelLinearizedReverse ct_rbd) + list(APPEND CT_MODELS_TARGETS HyQcompareForwardReverseFD) add_executable(HyQcompareForwardReverseID src/HyQ/codegen/compareForwardReverseID.cpp) target_link_libraries(HyQcompareForwardReverseID HyQJacInverseDynamicsForward HyQJacInverseDynamicsReverse ct_rbd) + list(APPEND CT_MODELS_TARGETS HyQcompareForwardReverseID) add_executable(HyQcompareForwardReverseKin src/HyQ/codegen/compareForwardReverseKin.cpp) target_link_libraries(HyQcompareForwardReverseKin HyQJacForwardKinForward HyQJacForwardKinReverse ct_rbd) + list(APPEND CT_MODELS_TARGETS HyQcompareForwardReverseKin) add_executable(HyQcompareForwardZero src/HyQ/codegen/compareForwardZero.cpp) - target_link_libraries(HyQcompareForwardZero - HyQForwardZero - ct_rbd) + target_link_libraries(HyQcompareForwardZero HyQForwardZero ct_rbd) + list(APPEND CT_MODELS_TARGETS HyQcompareForwardZero) endif(BUILD_HYQ_LINEARIZATION_TIMINGS) ########## Inverted Pendulum ######### -add_executable(InvertedPendulumWithActuatorCodeGen src/InvertedPendulum/codegen/InvertedPendulumWithActuatorCodeGen.cpp) -target_include_directories(InvertedPendulumWithActuatorCodeGen PUBLIC ${ct_models_target_include_dirs}) -target_link_libraries(InvertedPendulumWithActuatorCodeGen ct_rbd) +if(CPPADCG) + add_executable(InvertedPendulumWithActuatorCodeGen src/InvertedPendulum/codegen/InvertedPendulumWithActuatorCodeGen.cpp) + target_include_directories(InvertedPendulumWithActuatorCodeGen PUBLIC ${ct_models_target_include_dirs}) + target_link_libraries(InvertedPendulumWithActuatorCodeGen ct_rbd) + list(APPEND CT_MODELS_TARGETS InvertedPendulumWithActuatorCodeGen) +endif() add_library(InvertedPendulumActDynLinearizedForward include/ct/models/InvertedPendulum/codegen/InvertedPendulumActDynLinearizedForward.cpp) -target_include_directories(InvertedPendulumWithActuatorCodeGen PUBLIC ${ct_models_target_include_dirs}) +target_include_directories(InvertedPendulumActDynLinearizedForward PUBLIC ${ct_models_target_include_dirs}) target_link_libraries(InvertedPendulumActDynLinearizedForward ct_rbd) -list(APPEND CT_MODEL_LIBS InvertedPendulumActDynLinearizedForward) +list(APPEND CT_MODELS_TARGETS InvertedPendulumActDynLinearizedForward) ################ HyA ################# -add_executable(HyALinearizationCodegen src/HyA/codegen/HyALinearizationCodeGen.cpp) -target_include_directories(HyALinearizationCodegen PUBLIC ${ct_models_target_include_dirs}) -target_link_libraries(HyALinearizationCodegen ct_rbd) +if(CPPADCG) + add_executable(HyALinearizationCodegen src/HyA/codegen/HyALinearizationCodeGen.cpp) + target_include_directories(HyALinearizationCodegen PUBLIC ${ct_models_target_include_dirs}) + target_link_libraries(HyALinearizationCodegen ct_rbd) + list(APPEND CT_MODELS_TARGETS HyALinearizationCodegen) +endif() add_library(HyALinearizedForward include/ct/models/HyA/codegen/HyALinearizedForward.cpp) target_include_directories(HyALinearizedForward PUBLIC ${ct_models_target_include_dirs}) target_link_libraries(HyALinearizedForward ct_rbd ) -list(APPEND CT_MODEL_LIBS HyALinearizedForward) +list(APPEND CT_MODELS_TARGETS HyALinearizedForward) add_library(HyAJacInverseDynamicsReverse include/ct/models/HyA/codegen/HyAInverseDynJacReverse.cpp) target_include_directories(HyAJacInverseDynamicsReverse PUBLIC ${ct_models_target_include_dirs}) target_link_libraries(HyAJacInverseDynamicsReverse ct_rbd) -list(APPEND CT_MODEL_LIBS HyAJacInverseDynamicsReverse) +list(APPEND CT_MODELS_TARGETS HyAJacInverseDynamicsReverse) if(BUILD_HYA_LINEARIZATION_TIMINGS) add_library(HyALinearizedReverse include/ct/models/HyA/codegen/HyALinearizedReverse.cpp) target_include_directories(HyALinearizedReverse PUBLIC ${ct_models_target_include_dirs}) target_link_libraries(HyALinearizedReverse ct_rbd ) - list(APPEND CT_MODEL_LIBS HyALinearizedReverse) + list(APPEND CT_MODELS_TARGETS HyALinearizedReverse) add_library(HyAJacInverseDynamicsForward include/ct/models/HyA/codegen/HyAInverseDynJacForward.cpp) target_include_directories(HyAJacInverseDynamicsForward PUBLIC ${ct_models_target_include_dirs}) target_link_libraries(HyAJacInverseDynamicsForward ct_rbd ) - list(APPEND CT_MODEL_LIBS HyAJacInverseDynamicsForward) + list(APPEND CT_MODELS_TARGETS HyAJacInverseDynamicsForward) add_executable(HyAcompareForwardReverse src/HyA/codegen/compareForwardReverse.cpp) target_include_directories(HyAcompareForwardReverse PUBLIC ${ct_models_target_include_dirs}) @@ -157,6 +174,7 @@ if(BUILD_HYA_LINEARIZATION_TIMINGS) HyAJacInverseDynamicsReverse ct_rbd ) + list(APPEND CT_MODELS_TARGETS HyAcompareForwardReverse) endif(BUILD_HYA_LINEARIZATION_TIMINGS) @@ -169,7 +187,7 @@ add_library(quadrotorDynamics ) target_include_directories(quadrotorDynamics PUBLIC ${ct_models_target_include_dirs}) target_link_libraries(quadrotorDynamics ct_core) -list(APPEND CT_MODEL_LIBS quadrotorDynamics) +list(APPEND CT_MODELS_TARGETS quadrotorDynamics) ## Inverse Kinematics @@ -178,13 +196,13 @@ add_library(hya_ik src/HyA/transform6d.cpp) target_include_directories(hya_ik PUBLIC ${ct_models_target_include_dirs}) set_target_properties(hya_ik PROPERTIES COMPILE_FLAGS "-std=c++98 -fPIC -DIKFAST_NAMESPACE=hya_ik -DIKFAST_NO_MAIN -Wno-unused-variable") target_link_libraries(hya_ik ct_rbd) -list(APPEND CT_MODEL_LIBS hya_ik) +list(APPEND CT_MODELS_TARGETS hya_ik) add_library(irb4600_ik src/Irb4600/transform6d.cpp) target_include_directories(irb4600_ik PUBLIC ${ct_models_target_include_dirs}) set_target_properties(irb4600_ik PROPERTIES COMPILE_FLAGS "-std=c++98 -fPIC -DIKFAST_NAMESPACE=irb4600_ik -DIKFAST_NO_MAIN -Wno-unused-variable") target_link_libraries(irb4600_ik ct_rbd) -list(APPEND CT_MODEL_LIBS irb4600_ik) +list(APPEND CT_MODELS_TARGETS irb4600_ik) ## convenience library for passing on includes @@ -192,9 +210,9 @@ add_library(ct_models INTERFACE) target_include_directories(ct_models INTERFACE ${ct_models_target_include_dirs}) target_link_libraries(ct_models INTERFACE ct_rbd - ${CT_MODEL_LIBS} + ${CT_MODELS_TARGETS} ) -list(APPEND CT_MODEL_LIBS ct_models) +list(APPEND CT_MODELS_TARGETS ct_models) ############ @@ -231,7 +249,7 @@ install(FILES "cmake/ct_modelsConfig.cmake" DESTINATION "share/ct_models/cmake") ## install library and targets install( - TARGETS ${CT_MODEL_LIBS} + TARGETS ${CT_MODELS_TARGETS} EXPORT ct_models_export ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} diff --git a/ct_models/doc/ct_models.doxyfile b/ct_models/doc/ct_models.doxyfile index 8a1a302d1..61653c258 100644 --- a/ct_models/doc/ct_models.doxyfile +++ b/ct_models/doc/ct_models.doxyfile @@ -38,13 +38,13 @@ PROJECT_NAME = "" # could be handy for archiving the generated documentation or if some version # control system is used. -PROJECT_NUMBER = 3.0.1 +PROJECT_NUMBER = 3.0.2 # Using the PROJECT_BRIEF tag one can provide an optional one line description # for a project that appears at the top of each page and should give viewer a # quick idea about the purpose of the project. Keep the description short. -PROJECT_BRIEF = " - 3.0.1 models module." +PROJECT_BRIEF = " - 3.0.2 models module." # With the PROJECT_LOGO tag one can specify an logo or icon that is included in # the documentation. The maximum height of the logo should not exceed 55 pixels diff --git a/ct_models/examples/CMakeLists.txt b/ct_models/examples/CMakeLists.txt index 98c6b828b..eab67c232 100644 --- a/ct_models/examples/CMakeLists.txt +++ b/ct_models/examples/CMakeLists.txt @@ -2,12 +2,16 @@ set(CT_MODELS_EXAMPLE_DIR "${CMAKE_CURRENT_SOURCE_DIR}") configure_file(${CMAKE_CURRENT_SOURCE_DIR}/exampleDir.h.in ${CMAKE_CURRENT_SOURCE_DIR}/exampleDir.h) -add_executable(ex_NLOC_MPC_invertedPendulum mpc/InvertedPendulum/NLOC_MPC.cpp) -target_link_libraries(ex_NLOC_MPC_invertedPendulum ct_rbd) - -## install examples -include(GNUInstallDirs) -install( - TARGETS ex_NLOC_MPC_invertedPendulum - RUNTIME DESTINATION ${CMAKE_INSTALL_LIBDIR}/ct_models - ) \ No newline at end of file +if(CPPADCG) + add_executable(ex_NLOC_MPC_invertedPendulum mpc/InvertedPendulum/NLOC_MPC.cpp) + target_include_directories(ex_NLOC_MPC_invertedPendulum PUBLIC ${ct_models_target_include_dirs}) + target_link_libraries(ex_NLOC_MPC_invertedPendulum ct_rbd) + + ## install examples + include(GNUInstallDirs) + install( + TARGETS ex_NLOC_MPC_invertedPendulum + RUNTIME DESTINATION ${CMAKE_INSTALL_LIBDIR}/ct_models + ) + +endif() \ No newline at end of file diff --git a/ct_models/examples/mpc/InvertedPendulum/NLOC_MPC.cpp b/ct_models/examples/mpc/InvertedPendulum/NLOC_MPC.cpp index 35aeb9d91..2b4f07119 100644 --- a/ct_models/examples/mpc/InvertedPendulum/NLOC_MPC.cpp +++ b/ct_models/examples/mpc/InvertedPendulum/NLOC_MPC.cpp @@ -100,7 +100,7 @@ int main(int argc, char* argv[]) std::shared_ptr> newCost( new ct::optcon::CostFunctionAnalytical); size_t intTermID = newCost->addIntermediateTerm(termQuadInterm); - size_t finalTermID = newCost->addFinalTerm(termQuadFinal); + /*size_t finalTermID = */ newCost->addFinalTerm(termQuadFinal); ct::core::Time timeHorizon; InvertedPendulumNLOC::FeedbackArray::value_type fbD; diff --git a/ct_models/examples/mpc/InvertedPendulum/solver.info b/ct_models/examples/mpc/InvertedPendulum/solver.info index 96d01ca44..ff1116f5c 100644 --- a/ct_models/examples/mpc/InvertedPendulum/solver.info +++ b/ct_models/examples/mpc/InvertedPendulum/solver.info @@ -23,7 +23,6 @@ ilqr ;locp_solver HPIPM_SOLVER locp_solver GNRICCATI_SOLVER nlocp_algorithm GNMS - closedLoopShooting true printSummary true debugPrint false diff --git a/ct_models/include/ct/models/HyQ/HyQUrdfNames.h b/ct_models/include/ct/models/HyQ/HyQUrdfNames.h index 9c1b4860f..c863af407 100644 --- a/ct_models/include/ct/models/HyQ/HyQUrdfNames.h +++ b/ct_models/include/ct/models/HyQ/HyQUrdfNames.h @@ -5,6 +5,9 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-function" + namespace ct { namespace models { namespace HyQ { @@ -17,6 +20,9 @@ static std::vector urdfJointNames() return urdfJointNames; } -} -} -} + +} // namespace HyQ +} // namespace models +} // namespace ct + +#pragma GCC diagnostic pop diff --git a/ct_models/package.xml b/ct_models/package.xml index 2c5fec603..aff66367c 100755 --- a/ct_models/package.xml +++ b/ct_models/package.xml @@ -1,6 +1,6 @@ ct_models - 3.0.1 + 3.0.2 Control toolbox - models module. diff --git a/ct_models/src/HyQ/codegen/HyQLinearizationCodegen.cpp b/ct_models/src/HyQ/codegen/HyQLinearizationCodegen.cpp index d214b54c8..b1b9a1225 100644 --- a/ct_models/src/HyQ/codegen/HyQLinearizationCodegen.cpp +++ b/ct_models/src/HyQ/codegen/HyQLinearizationCodegen.cpp @@ -21,9 +21,6 @@ typedef ct::rbd::FloatingBaseFDSystem, false const size_t state_dim = HyQSystemAD::STATE_DIM; const size_t control_dim = HyQSystemAD::CONTROL_DIM; -// shortcut for number of joints -const size_t njoints = HyQSystemAD::Kinematics::NJOINTS; - void generateInverseDynamics() { @@ -102,7 +99,7 @@ void generateFDLinearization(int argc, char* argv[]) std::shared_ptr(new ContactModel(SCALAR(5000.0), SCALAR(1000.0), SCALAR(100.0), SCALAR(100.0), SCALAR(-0.02), ContactModel::VELOCITY_SMOOTHING::SIGMOID, adSystem->dynamics().kinematicsPtr())); - bool useContactModel = (argc <= 2 || !std::string(argv[2]).compare("nocontact") == 0); + bool useContactModel = (argc <= 2 || !(std::string(argv[2]).compare("nocontact") == 0)); std::cout << std::boolalpha << "using contact model: " << useContactModel << std::endl; // asign the contact model diff --git a/ct_optcon/CMakeLists.txt b/ct_optcon/CMakeLists.txt index 85fb66b02..7cad73003 100644 --- a/ct_optcon/CMakeLists.txt +++ b/ct_optcon/CMakeLists.txt @@ -3,9 +3,10 @@ cmake_minimum_required (VERSION 3.3) include(${CMAKE_CURRENT_SOURCE_DIR}/../ct/cmake/compilerSettings.cmake) include(${CMAKE_CURRENT_SOURCE_DIR}/../ct/cmake/explicitTemplateHelpers.cmake) include(${CMAKE_CURRENT_SOURCE_DIR}/../ct/cmake/clang-cxx-dev-tools.cmake) +include(${CMAKE_CURRENT_SOURCE_DIR}/../ct/cmake/ct-cmake-helpers.cmake) -project(ct_optcon VERSION 3.0.1 LANGUAGES CXX) +project(ct_optcon VERSION 3.0.2 LANGUAGES CXX) set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_SOURCE_DIR}/cmake") @@ -16,6 +17,8 @@ set(CMAKE_EXPORT_COMPILE_COMMANDS TRUE) ## find and include required dependencies find_package(ct_core REQUIRED) +# extract interface compile definitions from ct_core as options +importInterfaceCompileDefinitionsAsOptions(ct_core) ## find and include optional dependencies @@ -54,7 +57,7 @@ else(LAPACK_FOUND) endif(LAPACK_FOUND) -## include HPIPM (required: environment variables for blasfeo and hpipm set) +## include HPIPM find_package(blasfeo QUIET) find_package(hpipm QUIET) if(blasfeo_FOUND AND hpipm_FOUND) @@ -62,6 +65,8 @@ if(blasfeo_FOUND AND hpipm_FOUND) set(HPIPM ON) list(APPEND HPIPM_LIBS ${hpipm_LIBRARIES} ${blasfeo_LIBRARIES}) list(APPEND ct_optcon_COMPILE_DEFINITIONS HPIPM) +else() + message(WARNING "Could not find HPIPM or BLASFEO") endif() @@ -76,7 +81,7 @@ if(IPOPT_FOUND) endif() -## include SNOPT -- todo SNOPT not tested in version 3.0.1, temporarily deactivated +## include SNOPT -- todo SNOPT not tested in version 3.0.2, temporarily deactivated #set(SNOPT_TARGET "") #if(DEFINED ENV{SNOPT_SOURCE_DIR}) # set(BUILD_WITH_SNOPT_SUPPORT ON) diff --git a/ct_optcon/cmake/Findblasfeo.cmake b/ct_optcon/cmake/Findblasfeo.cmake index dab36f7d5..a7a0c77ce 100644 --- a/ct_optcon/cmake/Findblasfeo.cmake +++ b/ct_optcon/cmake/Findblasfeo.cmake @@ -1,15 +1,24 @@ -## find blasfeo library based on user-defined environment variable -if(DEFINED ENV{BLASFEO_DIR}) - message(STATUS "Found BLASFEO environment variable.") - list(APPEND blasfeo_INCLUDE_DIRS $ENV{BLASFEO_DIR}/include) +## ---------------------------------------------- +## find blasfeo library +## The Control Toolbox, Copyright M. Giftthaler +## ---------------------------------------------- - find_library(blasfeo_libs_found blasfeo $ENV{BLASFEO_DIR}/lib) +# default init +set(blasfeo_FOUND false) + +## if the user installed blasfeo to /opt/blasfeo, use find_package MODULE mode +IF(EXISTS "/opt/blasfeo") + message(STATUS "Found BLASFEO in /opt/blasfeo ...") + + list(APPEND blasfeo_INCLUDE_DIRS /opt/blasfeo/include) + + find_library(blasfeo_libs_found blasfeo /opt/blasfeo/lib) add_library(blasfeo STATIC IMPORTED) set_target_properties(blasfeo PROPERTIES IMPORTED_LOCATION ${blasfeo_libs_found}) set_target_properties(blasfeo PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "$ENV{BLASFEO_DIR}/include" + INTERFACE_INCLUDE_DIRECTORIES "/opt/blasfeo/include" INTERFACE_LINK_LIBRARIES ${blasfeo_libs_found} ) @@ -17,6 +26,17 @@ if(DEFINED ENV{BLASFEO_DIR}) set(blasfeo_FOUND true) else() - message(STATUS "No ENV variable for blasfeo found.") - set(blasfeo_FOUND false) + ## if the user installed blasfeo using cmake, fall back to find_package CONFIG mode + + find_package(blasfeo CONFIG) + + set(blasfeo_LIBRARIES blasfeo) + + if(blasfeo_FOUND) + message(STATUS "BLASFEO found in PACKAGE mode.") + endif() +endif() + +if(NOT blasfeo_FOUND) + message(STATUS "BLASFEO NOT found.") endif() \ No newline at end of file diff --git a/ct_optcon/cmake/Findhpipm.cmake b/ct_optcon/cmake/Findhpipm.cmake index e3514be22..68544f6c6 100644 --- a/ct_optcon/cmake/Findhpipm.cmake +++ b/ct_optcon/cmake/Findhpipm.cmake @@ -1,23 +1,42 @@ -## find hpipm library based on user-defined environment variable -if(DEFINED ENV{HPIPM_DIR}) - message(STATUS "Found HPIPM environment variable.") +## ---------------------------------------------- +## find hpipm library +## The Control Toolbox, Copyright M. Giftthaler +## ---------------------------------------------- + +# default init +set(hpipm_FOUND false) + +## if the user installed hpipm to /opt/hpipm, use find_package MODULE mode +IF(EXISTS "/opt/hpipm") + message(STATUS "Found HPIPM in /opt/hpipm ...") - list(APPEND hpipm_INCLUDE_DIRS $ENV{HPIPM_DIR}/include) + list(APPEND hpipm_INCLUDE_DIRS /opt/hpipm/include) - find_library(hpipm_libs_found hpipm $ENV{HPIPM_DIR}/lib) + find_library(hpipm_libs_found hpipm /opt/hpipm/lib) add_library(hpipm STATIC IMPORTED) set_target_properties(hpipm PROPERTIES IMPORTED_LOCATION ${hpipm_libs_found}) set_target_properties(hpipm PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "$ENV{HPIPM_DIR}/include" + INTERFACE_INCLUDE_DIRECTORIES "/opt/hpipm/include" INTERFACE_LINK_LIBRARIES ${hpipm_libs_found} ) + set(hpipm_LIBRARIES ${hpipm_libs_found}) set(hpipm_FOUND true) else() - message(STATUS "No ENV variable for HPIPM found.") - set(hpipm_FOUND false) + ## if the user installed hpipm using cmake, fall back to find_package CONFIG mode + + find_package(hpipm CONFIG) + + set(hpipm_LIBRARIES hpipm) + + if(hpipm_FOUND) + message(STATUS "HPIPM found in PACKAGE mode.") + endif() endif() +if(NOT hpipm_FOUND) + message(STATUS "HPIPM NOT found.") +endif() \ No newline at end of file diff --git a/ct_optcon/doc/ct_optcon.doxyfile b/ct_optcon/doc/ct_optcon.doxyfile index 05a1cee06..fc73c3231 100644 --- a/ct_optcon/doc/ct_optcon.doxyfile +++ b/ct_optcon/doc/ct_optcon.doxyfile @@ -38,13 +38,13 @@ PROJECT_NAME = # could be handy for archiving the generated documentation or if some version # control system is used. -PROJECT_NUMBER = 3.0.1 +PROJECT_NUMBER = 3.0.2 # Using the PROJECT_BRIEF tag one can provide an optional one line description # for a project that appears at the top of each page and should give viewer a # quick idea about the purpose of the project. Keep the description short. -PROJECT_BRIEF = " - 3.0.1 optimal control module." +PROJECT_BRIEF = " - 3.0.2 optimal control module." # With the PROJECT_LOGO tag one can specify an logo or icon that is included in # the documentation. The maximum height of the logo should not exceed 55 pixels diff --git a/ct_optcon/examples/CMakeLists.txt b/ct_optcon/examples/CMakeLists.txt index 2a53c4f24..1b01a602e 100644 --- a/ct_optcon/examples/CMakeLists.txt +++ b/ct_optcon/examples/CMakeLists.txt @@ -5,10 +5,6 @@ add_executable(ex_ConstraintOutput ConstraintExampleOutput.cpp) target_link_libraries(ex_ConstraintOutput ct_optcon) list(APPEND optcon_ex_TARGETS ex_ConstraintOutput) -add_executable(ex_LQR LQR.cpp) -target_link_libraries(ex_LQR ct_optcon) -list(APPEND optcon_ex_TARGETS ex_LQR) - add_executable(ex_NLOC NLOC.cpp) target_link_libraries(ex_NLOC ct_optcon) list(APPEND optcon_ex_TARGETS ex_NLOC) @@ -37,18 +33,26 @@ add_executable(ex_DMS DMS.cpp) target_link_libraries(ex_DMS ct_optcon) list(APPEND optcon_ex_TARGETS ex_DMS) +if(CPPADCG) + add_executable(ex_LQR LQR.cpp) + target_link_libraries(ex_LQR ct_optcon) + list(APPEND optcon_ex_TARGETS ex_LQR) +endif() + if(HPIPM) add_executable(ex_NLOC_boxConstrained NLOC_boxConstrained.cpp) target_link_libraries(ex_NLOC_boxConstrained ct_optcon) list(APPEND optcon_ex_TARGETS ex_NLOC_boxConstrained) - add_executable(ex_NLOC_generalConstrained NLOC_generalConstrained.cpp) - target_link_libraries(ex_NLOC_generalConstrained ct_optcon) - list(APPEND optcon_ex_TARGETS ex_NLOC_generalConstrained) + if(CPPADCG) + add_executable(ex_NLOC_generalConstrained NLOC_generalConstrained.cpp) + target_link_libraries(ex_NLOC_generalConstrained ct_optcon) + list(APPEND optcon_ex_TARGETS ex_NLOC_generalConstrained) - add_executable(switched_continuous_optcon_example switched_systems_optcon/switched_continuous_optcon.cpp) - target_link_libraries(switched_continuous_optcon_example ct_optcon) - list(APPEND optcon_ex_TARGETS switched_continuous_optcon_example) + add_executable(switched_continuous_optcon_example switched_systems_optcon/switched_continuous_optcon.cpp) + target_link_libraries(switched_continuous_optcon_example ct_optcon) + list(APPEND optcon_ex_TARGETS switched_continuous_optcon_example) + endif() endif(HPIPM) diff --git a/ct_optcon/examples/NLOC.cpp b/ct_optcon/examples/NLOC.cpp index d256dff6f..cc28b54dc 100644 --- a/ct_optcon/examples/NLOC.cpp +++ b/ct_optcon/examples/NLOC.cpp @@ -51,7 +51,7 @@ int main(int argc, char** argv) bool verbose = true; intermediateCost->loadConfigFile(ct::optcon::exampleDir + "/nlocCost.info", "intermediateCost", verbose); finalCost->loadConfigFile(ct::optcon::exampleDir + "/nlocCost.info", "finalCost", verbose); - + // Since we are using quadratic cost function terms in this example, the first and second order derivatives are immediately known and we // define the cost function to be an "Analytical Cost Function". Let's create the corresponding object and add the previously loaded // intermediate and final term. @@ -66,7 +66,7 @@ int main(int argc, char** argv) StateVector x0; x0.setRandom(); // in this example, we choose a random initial state x0 - ct::core::Time timeHorizon = 3.0; // and a final time horizon in [sec] + ct::core::Time timeHorizon = 1.0; // and a final time horizon in [sec] // STEP 1-E: create and initialize an "optimal control problem" @@ -81,25 +81,25 @@ int main(int argc, char** argv) * can be chosen using the following settings struct. Let's use, the iterative * linear quadratic regulator, iLQR, for this example. In the following, we * modify only a few settings, for more detail, check out the NLOptConSettings class. */ - NLOptConSettings ilqr_settings; - ilqr_settings.load(ct::optcon::exampleDir + "/nlocSolver.info", true, "ilqr"); + NLOptConSettings nloc_settings; + nloc_settings.load(ct::optcon::exampleDir + "/nlocSolver.info", true, "ilqr"); /* STEP 2-B: provide an initial guess */ // calculate the number of time steps K - size_t K = ilqr_settings.computeK(timeHorizon); + size_t K = nloc_settings.computeK(timeHorizon); /* design trivial initial controller for iLQR. Note that in this simple example, * we can simply use zero feedforward with zero feedback gains around the initial position. * In more complex examples, a more elaborate initial guess may be required.*/ FeedbackArray u0_fb(K, FeedbackMatrix::Zero()); - ControlVectorArray u0_ff(K, ControlVector::Zero()); + ControlVectorArray u0_ff(K, ControlVector::Random()); StateVectorArray x_ref_init(K + 1, x0); - NLOptConSolver::Policy_t initController(x_ref_init, u0_ff, u0_fb, ilqr_settings.dt); + NLOptConSolver::Policy_t initController(x_ref_init, u0_ff, u0_fb, nloc_settings.dt); // STEP 2-C: create an NLOptConSolver instance - NLOptConSolver iLQR(optConProblem, ilqr_settings); + NLOptConSolver iLQR(optConProblem, nloc_settings); // set the initial guess iLQR.setInitialGuess(initController); diff --git a/ct_optcon/examples/NLOC_boxConstrained.cpp b/ct_optcon/examples/NLOC_boxConstrained.cpp index 62d89109c..f6ce9f1da 100644 --- a/ct_optcon/examples/NLOC_boxConstrained.cpp +++ b/ct_optcon/examples/NLOC_boxConstrained.cpp @@ -70,33 +70,57 @@ int main(int argc, char** argv) u_ub = -u_lb; // constraint terms - std::shared_ptr> controlConstraint( + std::shared_ptr> controlInputBound( new ControlInputConstraint(u_lb, u_ub, sp_control)); - controlConstraint->setName("ControlInputConstraint"); + controlInputBound->setName("ControlInputBound"); - // create constraint container - std::shared_ptr> boxConstraints( + // input box constraint constraint container + std::shared_ptr> inputBoxConstraints( new ct::optcon::ConstraintContainerAnalytical()); // add and initialize constraint terms - boxConstraints->addIntermediateConstraint(controlConstraint, verbose); - boxConstraints->initialize(); + inputBoxConstraints->addIntermediateConstraint(controlInputBound, verbose); + inputBoxConstraints->initialize(); + + + /* STEP 1-E: set up the box constraints for the states */ + // state box constraint boundaries with sparsities in constraint toolbox format + // we put a box constraint on the velocity, hence the overall constraint dimension is 1. + Eigen::VectorXi sp_state(state_dim); + sp_state << 0, 1; + Eigen::VectorXd x_lb(1); + Eigen::VectorXd x_ub(1); + x_lb.setConstant(-0.2); + x_ub = -x_lb; + // constraint terms + std::shared_ptr> stateBound( + new StateConstraint(x_lb, x_ub, sp_state)); + stateBound->setName("StateBound"); + + // input box constraint constraint container + std::shared_ptr> stateBoxConstraints( + new ct::optcon::ConstraintContainerAnalytical()); + + // add and initialize constraint terms + stateBoxConstraints->addIntermediateConstraint(stateBound, verbose); + stateBoxConstraints->initialize(); - /* STEP 1-E: initialization with initial state and desired time horizon */ + /* STEP 1-F: initialization with initial state and desired time horizon */ StateVector x0; - x0.setRandom(); // in this example, we choose a random initial state x0 + x0.setZero(); // in this example, we choose a zero initial state ct::core::Time timeHorizon = 3.0; // and a final time horizon in [sec] - // STEP 1-E: create and initialize an "optimal control problem" + // STEP 1-G: create and initialize an "optimal control problem" ContinuousOptConProblem optConProblem( timeHorizon, x0, oscillatorDynamics, costFunction, adLinearizer); // add the box constraints to the optimal control problem - optConProblem.setBoxConstraints(boxConstraints); + optConProblem.setInputBoxConstraints(inputBoxConstraints); + optConProblem.setStateBoxConstraints(stateBoxConstraints); /* STEP 2: set up a nonlinear optimal control solver. */ @@ -110,8 +134,8 @@ int main(int argc, char** argv) ilqr_settings.integrator = ct::core::IntegrationType::EULERCT; ilqr_settings.discretization = NLOptConSettings::APPROXIMATION::FORWARD_EULER; ilqr_settings.max_iterations = 10; - ilqr_settings.nThreads = 4; - ilqr_settings.nlocp_algorithm = NLOptConSettings::NLOCP_ALGORITHM::ILQR; + ilqr_settings.nThreads = 1; + ilqr_settings.nlocp_algorithm = NLOptConSettings::NLOCP_ALGORITHM::GNMS; ilqr_settings.lqocp_solver = NLOptConSettings::LQOCP_SOLVER::HPIPM_SOLVER; // solve LQ-problems using HPIPM ilqr_settings.lqoc_solver_settings.num_lqoc_iterations = 10; // number of riccati sub-iterations ilqr_settings.printSummary = true; diff --git a/ct_optcon/examples/NLOC_generalConstrained.cpp b/ct_optcon/examples/NLOC_generalConstrained.cpp index 03cc89467..84a0fd05c 100644 --- a/ct_optcon/examples/NLOC_generalConstrained.cpp +++ b/ct_optcon/examples/NLOC_generalConstrained.cpp @@ -148,19 +148,8 @@ int main(int argc, char** argv) * Multiple Shooting for this example. In the following, we * modify only a few settings, for more detail, check out the NLOptConSettings class. */ NLOptConSettings nloc_settings; - nloc_settings.dt = 0.001; // the control discretization in [sec] - nloc_settings.integrator = ct::core::IntegrationType::EULERCT; - nloc_settings.discretization = NLOptConSettings::APPROXIMATION::FORWARD_EULER; - nloc_settings.max_iterations = 10; - nloc_settings.min_cost_improvement = 1e-4; - nloc_settings.nThreads = 1; - nloc_settings.nlocp_algorithm = NLOptConSettings::NLOCP_ALGORITHM::GNMS; + nloc_settings.load(ct::optcon::exampleDir + "/nlocSolver.info", true, "ilqr"); nloc_settings.lqocp_solver = NLOptConSettings::LQOCP_SOLVER::HPIPM_SOLVER; // solve LQ-problems using HPIPM - nloc_settings.lqoc_solver_settings.num_lqoc_iterations = 10; // number of riccati sub-iterations - nloc_settings.lineSearchSettings.active = false; - nloc_settings.lineSearchSettings.debugPrint = false; - nloc_settings.printSummary = true; - /* STEP 2-B: provide an initial guess */ // calculate the number of time steps K diff --git a/ct_optcon/examples/nlocSolver.info b/ct_optcon/examples/nlocSolver.info index 2d78bebbb..6f3ff6261 100644 --- a/ct_optcon/examples/nlocSolver.info +++ b/ct_optcon/examples/nlocSolver.info @@ -1,5 +1,6 @@ ilqr { + nlocp_algorithm GNMS integrator EulerCT useSensitivityIntegrator false discretization Forward_euler @@ -8,29 +9,33 @@ ilqr K_sim 1 K_shot 1 epsilon 0 - max_iterations 100 + max_iterations 12 fixedHessianCorrection false recordSmallestEigenvalue false min_cost_improvement 1e-5 maxDefectSum 1e-5 meritFunctionRho 0.0 meritFunctionRhoConstraints 0.0 - nThreads 4 - nThreadsEigen 4 + nThreads 1 + nThreadsEigen 1 locp_solver GNRICCATI_SOLVER - nlocp_algorithm ILQR - closedLoopShooting true printSummary true debugPrint false logToMatlab 0 line_search { - active false + type NONE adaptive false maxIterations 10 alpha_0 1.0 n_alpha 0.5 debugPrint true } + + lqoc_solver_settings + { + lqoc_debug_print false + num_lqoc_iterations 20 + } } \ No newline at end of file diff --git a/ct_optcon/examples/switched_systems_optcon/switched_continuous_optcon.cpp b/ct_optcon/examples/switched_systems_optcon/switched_continuous_optcon.cpp index 4d6d018c3..f86806e5f 100644 --- a/ct_optcon/examples/switched_systems_optcon/switched_continuous_optcon.cpp +++ b/ct_optcon/examples/switched_systems_optcon/switched_continuous_optcon.cpp @@ -142,7 +142,7 @@ int main(int argc, char** argv) ilqr_settings.nlocp_algorithm = NLOptConSettings::NLOCP_ALGORITHM::ILQR; ilqr_settings.lqocp_solver = NLOptConSettings::LQOCP_SOLVER::HPIPM_SOLVER; // solve LQ-problems using HPIPM ilqr_settings.lqoc_solver_settings.num_lqoc_iterations = 1000; // number of riccati sub-iterations - ilqr_settings.lineSearchSettings.active = true; + ilqr_settings.lineSearchSettings.type = LineSearchSettings::TYPE::SIMPLE; ilqr_settings.lineSearchSettings.debugPrint = true; ilqr_settings.printSummary = true; diff --git a/ct_optcon/include/ct/optcon/constraint/ConstraintContainerAD-impl.h b/ct_optcon/include/ct/optcon/constraint/ConstraintContainerAD-impl.h index 43ab3a441..ad47ac6e1 100644 --- a/ct_optcon/include/ct/optcon/constraint/ConstraintContainerAD-impl.h +++ b/ct_optcon/include/ct/optcon/constraint/ConstraintContainerAD-impl.h @@ -5,6 +5,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once +#ifdef CPPADCG + namespace ct { namespace optcon { @@ -568,3 +570,5 @@ ConstraintContainerAD::evaluateTerminalCodegen( } // namespace optcon } // namespace ct + +#endif diff --git a/ct_optcon/include/ct/optcon/constraint/ConstraintContainerAD.h b/ct_optcon/include/ct/optcon/constraint/ConstraintContainerAD.h index 779e050d5..3b71d9340 100644 --- a/ct_optcon/include/ct/optcon/constraint/ConstraintContainerAD.h +++ b/ct_optcon/include/ct/optcon/constraint/ConstraintContainerAD.h @@ -5,6 +5,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once +#ifdef CPPADCG + #include "LinearConstraintContainer.h" #include "term/ConstraintBase.h" @@ -185,3 +187,5 @@ class ConstraintContainerAD : public LinearConstraintContainer::getFinalADTermByName(const std:: } } // namespace optcon } // namespace ct + +#endif diff --git a/ct_optcon/include/ct/optcon/costfunction/CostFunctionAD.hpp b/ct_optcon/include/ct/optcon/costfunction/CostFunctionAD.hpp index 36372e7b6..de22b7b33 100644 --- a/ct_optcon/include/ct/optcon/costfunction/CostFunctionAD.hpp +++ b/ct_optcon/include/ct/optcon/costfunction/CostFunctionAD.hpp @@ -5,6 +5,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once +#ifdef CPPADCG + #include #include @@ -66,7 +68,7 @@ class CostFunctionAD : public CostFunctionQuadratic* clone() const; + CostFunctionAD* clone() const override; /** * \brief Copy constructor @@ -166,3 +168,5 @@ class CostFunctionAD : public CostFunctionQuadratic* clone() const; + CostFunctionAnalytical* clone() const override; /** * Destructor diff --git a/ct_optcon/include/ct/optcon/costfunction/term/TermQuadMult.hpp b/ct_optcon/include/ct/optcon/costfunction/term/TermQuadMult.hpp index d620046b7..9bb731763 100644 --- a/ct_optcon/include/ct/optcon/costfunction/term/TermQuadMult.hpp +++ b/ct_optcon/include/ct/optcon/costfunction/term/TermQuadMult.hpp @@ -81,7 +81,7 @@ class TermQuadMult : public TermBase& u, const SCALAR_EVAL& t) override; - void loadConfigFile(const std::string& filename, const std::string& termName, bool verbose = false); + void loadConfigFile(const std::string& filename, const std::string& termName, bool verbose = false) override; protected: diff --git a/ct_optcon/include/ct/optcon/dms/dms_core/DmsProblem.h b/ct_optcon/include/ct/optcon/dms/dms_core/DmsProblem.h index e3d9d7f19..2fbf7d175 100644 --- a/ct_optcon/include/ct/optcon/dms/dms_core/DmsProblem.h +++ b/ct_optcon/include/ct/optcon/dms/dms_core/DmsProblem.h @@ -54,7 +54,8 @@ class DmsProblem : public tpl::Nlp * @param[in] systemPtrs The non linear systems * @param[in] linearPtrs The linearized systems * @param[in] costPtrs The cost function - * @param[in] boxConstraints The box constraints + * @param[in] inputBoxConstraints The input box constraints + * @param[in] stateBoxConstraints The state box constraints * @param[in] generaConstraints The general constraints * @param[in] x0 The initial state */ @@ -62,7 +63,8 @@ class DmsProblem : public tpl::Nlp std::vector systemPtrs, std::vector linearPtrs, std::vector costPtrs, - std::vector boxConstraints, + std::vector inputBoxConstraints, + std::vector stateBoxConstraints, std::vector generalConstraints, const state_vector_t& x0) : settings_(settings) @@ -104,13 +106,20 @@ class DmsProblem : public tpl::Nlp optVariablesDms_ = std::static_pointer_cast>(this->optVariables_); - if (boxConstraints.size() > 0 || generalConstraints.size() > 0) + if (inputBoxConstraints.size() > 0 || stateBoxConstraints.size() > 0 || generalConstraints.size() > 0) discretizedConstraints_ = std::shared_ptr>( new ConstraintDiscretizer( optVariablesDms_, controlSpliner_, timeGrid_, settings_.N_)); - if (boxConstraints.size() > 0) - discretizedConstraints_->setBoxConstraints(boxConstraints.front()); + if (inputBoxConstraints.size() > 0) + discretizedConstraints_->setBoxConstraints( + inputBoxConstraints + .front()); // at this point we do not distinguish between state and input box constraints + + if (stateBoxConstraints.size() > 0) + discretizedConstraints_->setBoxConstraints( + stateBoxConstraints + .front()); // at this point we do not distinguish between state and input box constraints if (generalConstraints.size() > 0) discretizedConstraints_->setGeneralConstraints(generalConstraints.front()); @@ -159,153 +168,6 @@ class DmsProblem : public tpl::Nlp this->optVariables_->resizeConstraintVars(this->getConstraintsCount()); } - void generateAndCompileCode( - std::vector>> systemPtrs, - std::vector>> linearPtrs, - std::vector>> - costPtrs, - std::vector>> - boxConstraints, - std::vector>> - generalConstraints, - const ct::core::StateVector& x0) - { - typedef ct::core::ADCGScalar ScalarCG; - size_t wLength = (settings_.N_ + 1) * (STATE_DIM + CONTROL_DIM); - - std::shared_ptr> timeGrid( - new tpl::TimeGrid(settings_.N_, ScalarCG(settings_.T_))); - - std::shared_ptr, ScalarCG>> controlSpliner; - - switch (settings_.splineType_) - { - case DmsSettings::ZERO_ORDER_HOLD: - { - controlSpliner = - std::shared_ptr, ScalarCG>>( - new ZeroOrderHoldSpliner, ScalarCG>(timeGrid)); - break; - } - case DmsSettings::PIECEWISE_LINEAR: - { - controlSpliner = - std::shared_ptr, ScalarCG>>( - new LinearSpliner, ScalarCG>(timeGrid)); - break; - } - default: - throw(std::runtime_error("Unknown spline type")); - } - - std::shared_ptr> optVariablesDms( - new OptVectorDms(wLength, settings_)); - - - std::shared_ptr> discretizedConstraints; - if (boxConstraints.size() > 0 || generalConstraints.size() > 0) - discretizedConstraints = std::shared_ptr>( - new ConstraintDiscretizer( - optVariablesDms, controlSpliner, timeGrid, settings_.N_)); - - if (boxConstraints.size() > 0) - discretizedConstraints->setBoxConstraints(boxConstraints.front()); - - if (generalConstraints.size() > 0) - discretizedConstraints->setGeneralConstraints(generalConstraints.front()); - - std::vector>> shotContainers; - for (size_t shotIdx = 0; shotIdx < settings_.N_; shotIdx++) - { - std::shared_ptr> newController( - new ControllerDms(controlSpliner, shotIdx)); - systemPtrs[shotIdx]->setController(newController); - linearPtrs[shotIdx]->setController(newController); - - size_t nIntegrationSteps = - (timeGrid_->getShotEndTime(shotIdx) - timeGrid_->getShotStartTime(shotIdx)) / settings_.dt_sim_ + 0.5; - - shotContainers.push_back(std::shared_ptr>( - new ShotContainer(systemPtrs[shotIdx], linearPtrs[shotIdx], - costPtrs[shotIdx], optVariablesDms, controlSpliner, timeGrid, shotIdx, settings_, - nIntegrationSteps))); - } - - std::shared_ptr> costEvaluator; - - switch (settings_.costEvaluationType_) - { - case DmsSettings::SIMPLE: - { - costEvaluator = std::shared_ptr>( - new CostEvaluatorSimple( - costPtrs.front(), optVariablesDms, timeGrid, settings_)); - break; - } - case DmsSettings::FULL: - { - costEvaluator = std::shared_ptr>( - new CostEvaluatorFull( - costPtrs.front(), optVariablesDms, controlSpliner, shotContainers, settings_)); - break; - } - default: - throw(std::runtime_error("Unknown cost evaluation type")); - } - - optVariablesDms->resizeConstraintVars(this->getConstraintsCount()); - - std::shared_ptr> constraints( - new ConstraintsContainerDms( - optVariablesDms, timeGrid, shotContainers, discretizedConstraints, x0, settings_)); - - if (settings_.solverSettings_.useGeneratedCostGradient_) - { - std::function(const Eigen::Matrix&)> fCost = [&]( - const Eigen::Matrix& xOpt) { - optVariablesDms->setOptimizationVars(xOpt); - - controlSpliner->computeSpline(optVariablesDms->getOptimizedInputs().toImplementation()); - for (auto shotContainer : shotContainers) - shotContainer->reset(); - - Eigen::Matrix out; - out << costEvaluator->eval(); - return out; - }; - - settings_.cppadSettings_.createJacobian_ = true; - - this->costCodegen_ = std::shared_ptr>( - new ct::core::DerivativesCppadJIT<-1, 1>(fCost, this->getVarCount())); - this->costCodegen_->compileJIT(settings_.cppadSettings_, "dmsCostFunction"); - } - - if (settings_.solverSettings_.useGeneratedConstraintJacobian_) - { - std::function(const Eigen::Matrix&)> - fConstraints = [&](const Eigen::Matrix& xOpt) { - optVariablesDms->setOptimizationVars(xOpt); - - controlSpliner->computeSpline(optVariablesDms->getOptimizedInputs().toImplementation()); - for (auto shotContainer : shotContainers) - shotContainer->reset(); - - - Eigen::Matrix out( - this->getConstraintsCount()); // out.resize(this->getConstraintsCount, 1); - constraints->evalConstraints(out); - return out; - }; - - settings_.cppadSettings_.createJacobian_ = false; - - this->constraintsCodegen_ = - std::shared_ptr>(new ct::core::DerivativesCppadJIT<-1, -1>( - fConstraints, this->getVarCount(), this->getConstraintsCount())); - this->constraintsCodegen_->compileJIT(settings_.cppadSettings_, "dmsConstraints"); - } - } /** * @brief Destructor @@ -402,6 +264,7 @@ class DmsProblem : public tpl::Nlp * @brief Prints the solution trajectories */ void printSolution() { optVariablesDms_->printoutSolution(); } + private: DmsSettings settings_; diff --git a/ct_optcon/include/ct/optcon/dms/dms_core/DmsSolver.h b/ct_optcon/include/ct/optcon/dms/dms_core/DmsSolver.h index c6b5ce1ff..d09b396b4 100644 --- a/ct_optcon/include/ct/optcon/dms/dms_core/DmsSolver.h +++ b/ct_optcon/include/ct/optcon/dms/dms_core/DmsSolver.h @@ -96,9 +96,10 @@ class DmsSolver : public OptConSolver, // Create system, linearsystem and costfunction instances this->setProblem(problem); - dmsProblem_ = std::shared_ptr>( - new DmsProblem(settingsDms, this->systems_, this->linearSystems_, - this->costFunctions_, this->boxConstraints_, this->generalConstraints_, x0_)); + dmsProblem_ = + std::shared_ptr>(new DmsProblem( + settingsDms, this->systems_, this->linearSystems_, this->costFunctions_, this->inputBoxConstraints_, + this->stateBoxConstraints_, this->generalConstraints_, x0_)); // SNOPT only works for the double type if (settingsDms.solverSettings_.solverType_ == NlpSolverType::SNOPT) @@ -111,39 +112,6 @@ class DmsSolver : public OptConSolver, configure(settingsDms); } - void generateAndCompileCode(const ContinuousOptConProblem& problemCG, - const ct::core::DerivativesCppadSettings& settings) override - { - // Create system, linearsystem and costfunction instances - typedef std::shared_ptr> SysPtrCG; - typedef std::shared_ptr> LinearSysPtrCG; - typedef std::shared_ptr> CostPtrCG; - typedef std::shared_ptr> - ConstraintCG; - ct::core::StateVector x0CG = problemCG.getInitialState(); - - std::vector systemsCG; - std::vector linearSystemsCG; - std::vector costFunctionsCG; - std::vector boxConstraintsCG; - std::vector generalConstraintsCG; - - for (size_t i = 0; i < settings_.N_; i++) - { - systemsCG.push_back(SysPtrCG(problemCG.getNonlinearSystem()->clone())); - linearSystemsCG.push_back(LinearSysPtrCG(problemCG.getLinearSystem()->clone())); - costFunctionsCG.push_back(CostPtrCG(problemCG.getCostFunction()->clone())); - } - - if (problemCG.getBoxConstraints()) - boxConstraintsCG.push_back(ConstraintCG(problemCG.getBoxConstraints()->clone())); - - if (problemCG.getGeneralConstraints()) - generalConstraintsCG.push_back(ConstraintCG(problemCG.getGeneralConstraints()->clone())); - - dmsProblem_->generateAndCompileCode( - systemsCG, linearSystemsCG, costFunctionsCG, boxConstraintsCG, generalConstraintsCG, x0CG); - } /** * @brief Destructor @@ -231,9 +199,16 @@ class DmsSolver : public OptConSolver, this->getLinearSystemsInstances()[i] = typename Base::OptConProblem_t::LinearPtr_t(lin->clone()); } - void changeBoxConstraints(const typename Base::OptConProblem_t::ConstraintPtr_t con) override + void changeInputBoxConstraints(const typename Base::OptConProblem_t::ConstraintPtr_t con) override { - this->getBoxConstraintsInstances().push_back(typename Base::OptConProblem_t::ConstraintPtr_t(con->clone())); + this->getInputBoxConstraintsInstances().push_back( + typename Base::OptConProblem_t::ConstraintPtr_t(con->clone())); + } + + void changeStateBoxConstraints(const typename Base::OptConProblem_t::ConstraintPtr_t con) override + { + this->getStateBoxConstraintsInstances().push_back( + typename Base::OptConProblem_t::ConstraintPtr_t(con->clone())); } void changeGeneralConstraints(const typename Base::OptConProblem_t::ConstraintPtr_t con) override @@ -266,13 +241,24 @@ class DmsSolver : public OptConSolver, return costFunctions_; } - std::vector& getBoxConstraintsInstances() override + std::vector& getInputBoxConstraintsInstances() override { - return boxConstraints_; + return inputBoxConstraints_; } - const std::vector& getBoxConstraintsInstances() const override + + const std::vector& getInputBoxConstraintsInstances() const override + { + return inputBoxConstraints_; + } + + std::vector& getStateBoxConstraintsInstances() override + { + return stateBoxConstraints_; + } + + const std::vector& getStateBoxConstraintsInstances() const override { - return boxConstraints_; + return stateBoxConstraints_; } std::vector& getGeneralConstraintsInstances() override @@ -298,7 +284,8 @@ class DmsSolver : public OptConSolver, std::vector systems_; std::vector linearSystems_; std::vector costFunctions_; - std::vector boxConstraints_; + std::vector inputBoxConstraints_; + std::vector stateBoxConstraints_; std::vector generalConstraints_; }; diff --git a/ct_optcon/include/ct/optcon/nloc/NLOCBackendBase-impl.hpp b/ct_optcon/include/ct/optcon/nloc/NLOCBackendBase-impl.hpp index 165292b65..be976d3d1 100644 --- a/ct_optcon/include/ct/optcon/nloc/NLOCBackendBase-impl.hpp +++ b/ct_optcon/include/ct/optcon/nloc/NLOCBackendBase-impl.hpp @@ -34,29 +34,27 @@ NLOCBackendBase::NLOCB : initialized_(false), configured_(false), iteration_(0), + firstRollout_(true), settings_(settings), K_(0), + substepsX_(new StateSubsteps), + substepsU_(new ControlSubsteps), d_norm_(0.0), e_box_norm_(0.0), e_gen_norm_(0.0), lx_norm_(0.0), lu_norm_(0.0), - lqocProblem_(new LQOCProblem()), - - substepsX_(new StateSubsteps), - substepsU_(new ControlSubsteps), - - systemInterface_(systemInterface), - intermediateCostBest_(std::numeric_limits::infinity()), finalCostBest_(std::numeric_limits::infinity()), lowestCost_(std::numeric_limits::infinity()), intermediateCostPrevious_(std::numeric_limits::infinity()), finalCostPrevious_(std::numeric_limits::infinity()), - boxConstraints_(settings.nThreads + 1, nullptr), // initialize constraints with null - generalConstraints_(settings.nThreads + 1, nullptr), // initialize constraints with null - firstRollout_(true), alphaBest_(-1), + lqocProblem_(new LQOCProblem()), + systemInterface_(systemInterface), + inputBoxConstraints_(settings.nThreads + 1, nullptr), // initialize constraints with null + stateBoxConstraints_(settings.nThreads + 1, nullptr), // initialize constraints with null + generalConstraints_(settings.nThreads + 1, nullptr), // initialize constraints with null lqpCounter_(0) { Eigen::initParallel(); @@ -70,8 +68,11 @@ NLOCBackendBase::NLOCB changeCostFunction(systemInterface_->getOptConProblem().getCostFunction()); // if the optimal problem has constraints, change - if (systemInterface_->getOptConProblem().getBoxConstraints()) - changeBoxConstraints(systemInterface_->getOptConProblem().getBoxConstraints()); + if (systemInterface_->getOptConProblem().getInputBoxConstraints()) + changeInputBoxConstraints(systemInterface_->getOptConProblem().getInputBoxConstraints()); + if (systemInterface_->getOptConProblem().getStateBoxConstraints()) + changeStateBoxConstraints(systemInterface_->getOptConProblem().getStateBoxConstraints()); + if (systemInterface_->getOptConProblem().getGeneralConstraints()) changeGeneralConstraints(systemInterface_->getOptConProblem().getGeneralConstraints()); } @@ -144,6 +145,7 @@ void NLOCBackendBase:: L_ = initialGuess.K(); x_ = initialGuess.x_ref(); x_prev_ = x_; + x_ref_lqr_ = x_; if (x_.size() > (size_t)K_ + 1) { @@ -194,9 +196,13 @@ void NLOCBackendBase:: x_.resize(K_ + 1); x_prev_.resize(K_ + 1); xShot_.resize(K_ + 1); + delta_x_.resize(K_ + 1); + x_ref_lqr_.resize(K_ + 1); + delta_x_ref_lqr_.resize(K_ + 1); u_ff_.resize(K_); u_ff_prev_.resize(K_); + delta_u_ff_.resize(K_); d_.resize(K_ + 1); L_.resize(K_); @@ -250,7 +256,7 @@ void NLOCBackendBase:: // recompute cost if line search is active // TODO: this should be multi-threaded to save time - if (iteration_ > 0 && settings_.lineSearchSettings.active) + if (iteration_ > 0 && (settings_.lineSearchSettings.type != LineSearchSettings::TYPE::NONE)) computeCostsOfTrajectory(settings_.nThreads, x_, u_ff_, intermediateCostBest_, finalCostBest_); } @@ -262,29 +268,54 @@ void NLOCBackendBase:: } template -void NLOCBackendBase::changeBoxConstraints( +void NLOCBackendBase::changeInputBoxConstraints( const typename OptConProblem_t::ConstraintPtr_t& con) { if (con == nullptr) throw std::runtime_error("NLOCBackendBase: box constraint is nullptr"); - boxConstraints_.resize(settings_.nThreads + 1); + inputBoxConstraints_.resize(settings_.nThreads + 1); for (int i = 0; i < settings_.nThreads + 1; i++) { // make a deep copy - boxConstraints_[i] = typename OptConProblem_t::ConstraintPtr_t(con->clone()); + inputBoxConstraints_[i] = typename OptConProblem_t::ConstraintPtr_t(con->clone()); } // TODO can we do this multi-threaded? - if (iteration_ > 0 && settings_.lineSearchSettings.active) + if (iteration_ > 0 && (settings_.lineSearchSettings.type != LineSearchSettings::TYPE::NONE)) computeBoxConstraintErrorOfTrajectory(settings_.nThreads, x_, u_ff_, e_box_norm_); - setBoxConstraintsForLQOCProblem(); - lqocSolver_->configureBoxConstraints(lqocProblem_); - lqocSolver_->initializeAndAllocate(); + setInputBoxConstraintsForLQOCProblem(); + lqocSolver_->configureInputBoxConstraints(lqocProblem_); + lqocSolver_->initializeAndAllocate(); // todo - this is not nice +} + +template +void NLOCBackendBase::changeStateBoxConstraints( + const typename OptConProblem_t::ConstraintPtr_t& con) +{ + if (con == nullptr) + throw std::runtime_error("NLOCBackendBase: box constraint is nullptr"); + + stateBoxConstraints_.resize(settings_.nThreads + 1); + + for (int i = 0; i < settings_.nThreads + 1; i++) + { + // make a deep copy + stateBoxConstraints_[i] = typename OptConProblem_t::ConstraintPtr_t(con->clone()); + } + + // TODO can we do this multi-threaded? + if (iteration_ > 0 && (settings_.lineSearchSettings.type != LineSearchSettings::TYPE::NONE)) + computeBoxConstraintErrorOfTrajectory(settings_.nThreads, x_, u_ff_, e_box_norm_); + + setStateBoxConstraintsForLQOCProblem(); + lqocSolver_->configureStateBoxConstraints(lqocProblem_); + lqocSolver_->initializeAndAllocate(); // todo - this is not nice } + template void NLOCBackendBase::changeGeneralConstraints( const typename OptConProblem_t::ConstraintPtr_t& con) @@ -300,21 +331,32 @@ void NLOCBackendBase:: generalConstraints_[i] = typename OptConProblem_t::ConstraintPtr_t(con->clone()); } - // we need to allocate memory in HPIPM for the new constraints + // intermediate stages for (int i = 0; i < K_; i++) { - generalConstraints_[settings_.nThreads]->setCurrentStateAndControl( - lqocProblem_->x_[i], lqocProblem_->u_[i], i * settings_.dt); + generalConstraints_[settings_.nThreads]->setCurrentStateAndControl(x_[i], u_ff_[i], i * settings_.dt); + lqocProblem_->ng_[i] = generalConstraints_[settings_.nThreads]->getIntermediateConstraintsCount(); + + lqocProblem_->C_[i].resize(lqocProblem_->ng_[i], STATE_DIM); + lqocProblem_->D_[i].resize(lqocProblem_->ng_[i], CONTROL_DIM); + lqocProblem_->d_lb_[i].resize(lqocProblem_->ng_[i], 1); + lqocProblem_->d_ub_[i].resize(lqocProblem_->ng_[i], 1); } + // terminal stage lqocProblem_->ng_[K_] = generalConstraints_[settings_.nThreads]->getTerminalConstraintsCount(); + lqocProblem_->C_[K_].resize(lqocProblem_->ng_[K_], STATE_DIM); + lqocProblem_->D_[K_].resize(lqocProblem_->ng_[K_], CONTROL_DIM); + lqocProblem_->d_lb_[K_].resize(lqocProblem_->ng_[K_], 1); + lqocProblem_->d_ub_[K_].resize(lqocProblem_->ng_[K_], 1); + lqocSolver_->setProblem(lqocProblem_); lqocSolver_->configureGeneralConstraints(lqocProblem_); lqocSolver_->initializeAndAllocate(); // TODO can we do this multi-threaded? - if (iteration_ > 0 && settings_.lineSearchSettings.active) + if (iteration_ > 0 && (settings_.lineSearchSettings.type != LineSearchSettings::TYPE::NONE)) computeGeneralConstraintErrorOfTrajectory(settings_.nThreads, x_, u_ff_, e_gen_norm_); } @@ -395,7 +437,7 @@ bool NLOCBackendBase:: const size_t k, //! the starting index of the shot ControlVectorArray& u_local, StateVectorArray& x_local, - const StateVectorArray& x_ref_lqr, + const StateVectorArray& x_ref_lqr_local, StateVectorArray& xShot, //! the value at the end of each integration interval StateSubsteps& substepsX, ControlSubsteps& substepsU, @@ -428,9 +470,8 @@ bool NLOCBackendBase:: xShot[i] = xShot[i - 1]; //! initialize integration variable } - // Todo: the order here is not optimal. In some cases, we will overwrite x_ref_lqr immediately in the next step! - if (settings_.closedLoopShooting) // overwrite control - u_local[i] += L_[i] * (xShot[i] - x_ref_lqr[i]); + if (settings_.closedLoopShooting()) // overwrite control + u_local[i] += L_[i] * (xShot[i] - x_ref_lqr_local[i]); //! @todo: here we override the state trajectory directly (as passed by reference). This is bad. if (i > (int)k) @@ -563,12 +604,23 @@ void NLOCBackendBase:: // intermediate constraints for (size_t k = 0; k < (size_t)K_; k++) { - if (boxConstraints_[threadId] != nullptr) + if (inputBoxConstraints_[threadId] != nullptr) + { + if (inputBoxConstraints_[threadId]->getIntermediateConstraintsCount() > 0) + { + inputBoxConstraints_[threadId]->setCurrentStateAndControl(x_local[k], u_local[k], settings_.dt * k); + Eigen::Matrix box_err = + inputBoxConstraints_[threadId]->getTotalBoundsViolationIntermediate(); + e_tot += box_err.template lpNorm<1>(); + } + } + if (stateBoxConstraints_[threadId] != nullptr) { - if (boxConstraints_[threadId]->getIntermediateConstraintsCount() > 0) + if (stateBoxConstraints_[threadId]->getIntermediateConstraintsCount() > 0) { - boxConstraints_[threadId]->setCurrentStateAndControl(x_local[k], u_local[k], settings_.dt * k); - Eigen::Matrix box_err = boxConstraints_[threadId]->getTotalBoundsViolationIntermediate(); + stateBoxConstraints_[threadId]->setCurrentStateAndControl(x_local[k], u_local[k], settings_.dt * k); + Eigen::Matrix box_err = + stateBoxConstraints_[threadId]->getTotalBoundsViolationIntermediate(); e_tot += box_err.template lpNorm<1>(); } } @@ -578,13 +630,13 @@ void NLOCBackendBase:: e_tot *= settings_.dt; // terminal constraint violation - if (boxConstraints_[threadId] != nullptr) + if (stateBoxConstraints_[threadId] != nullptr) { - if (boxConstraints_[threadId]->getTerminalConstraintsCount() > 0) + if (stateBoxConstraints_[threadId]->getTerminalConstraintsCount() > 0) { - boxConstraints_[threadId]->setCurrentStateAndControl( + stateBoxConstraints_[threadId]->setCurrentStateAndControl( x_local[K_], control_vector_t::Zero(), settings_.dt * K_); - Eigen::Matrix box_err = boxConstraints_[threadId]->getTotalBoundsViolationTerminal(); + Eigen::Matrix box_err = stateBoxConstraints_[threadId]->getTotalBoundsViolationTerminal(); e_tot += box_err.template lpNorm<1>(); } } @@ -638,10 +690,6 @@ void NLOCBackendBase:: assert(lqocProblem_ != nullptr); - assert(&lqocProblem_->A_[k] != nullptr); - assert(&lqocProblem_->B_[k] != nullptr); - assert(&lqocProblem_->b_[k] != nullptr); - assert(lqocProblem_->A_.size() > k); assert(lqocProblem_->B_.size() > k); assert(lqocProblem_->b_.size() > k); @@ -653,7 +701,7 @@ void NLOCBackendBase:: systemInterface_->getAandB(x_[k], u_ff_[k], xShot_[k], (int)k, settings_.K_sim, p.A_[k], p.B_[k], threadId); // compute dynamics offset term b_n - p.b_[k] = d_[k] + x_[k + 1] - p.A_[k] * x_[k] - p.B_[k] * u_ff_[k]; + p.b_[k] = d_[k]; // feed current state and control to cost function costFunctions_[threadId]->setCurrentStateAndControl(x_[k], u_ff_[k], dt * k); @@ -667,70 +715,73 @@ void NLOCBackendBase:: p.P_[k] = costFunctions_[threadId]->stateControlDerivativeIntermediate() * dt; // derivative of cost with respect to state - p.qv_[k] = - costFunctions_[threadId]->stateDerivativeIntermediate() * dt - p.Q_[k] * x_[k] - p.P_[k].transpose() * u_ff_[k]; + p.qv_[k] = costFunctions_[threadId]->stateDerivativeIntermediate() * dt; // derivative of cost with respect to control - p.rv_[k] = costFunctions_[threadId]->controlDerivativeIntermediate() * dt - p.R_[k] * u_ff_[k] - p.P_[k] * x_[k]; + p.rv_[k] = costFunctions_[threadId]->controlDerivativeIntermediate() * dt; // p.q_[k] = ... // not evaluated since we don't need it in GNMS/iLQR -- WARNING, potentially implement when using a different QP solver - - // set current reference trajectories x_n and u_n - p.x_[k] = x_[k]; - p.u_[k] = u_ff_[k]; } + template -void NLOCBackendBase::setBoxConstraintsForLQOCProblem() +void NLOCBackendBase::setInputBoxConstraintsForLQOCProblem() { // set box constraints if there are any - if (boxConstraints_[settings_.nThreads] != nullptr) + if (inputBoxConstraints_[settings_.nThreads] != nullptr) { - // temp vars - Eigen::VectorXi u_sparsity_row, x_sparsity_row, u_sparsity_col_intermediate, x_sparsity_col_intermediate, - x_sparsity_col_terminal; - - // intermediate box constraints - const int nb_ux_intermediate = boxConstraints_[settings_.nThreads]->getJacobianStateNonZeroCountIntermediate() + - boxConstraints_[settings_.nThreads]->getJacobianInputNonZeroCountIntermediate(); + // check number of intermediate box constraints + const int nb_u_intermediate = + inputBoxConstraints_[settings_.nThreads]->getJacobianInputNonZeroCountIntermediate(); - if (nb_ux_intermediate > 0) + if (nb_u_intermediate > 0) { - boxConstraints_[settings_.nThreads]->sparsityPatternInputIntermediate( + Eigen::VectorXi u_sparsity_row, u_sparsity_col_intermediate; + + inputBoxConstraints_[settings_.nThreads]->sparsityPatternInputIntermediate( u_sparsity_row, u_sparsity_col_intermediate); - boxConstraints_[settings_.nThreads]->sparsityPatternStateIntermediate( - x_sparsity_row, x_sparsity_col_intermediate); - // WARNING (TODO): currently, we require input box constraints to be added before state box constraints. - // We can check for correct ordering: if two types of box constraints are present ... - if (u_sparsity_row.size() > 0 && x_sparsity_row.size() > 0) - { - // ... we can check for correct ordering by comparing row indices. In case of wrong ordering, throw exception (TODO improve). - if (u_sparsity_row.array().minCoeff() > x_sparsity_row.array().maxCoeff()) - throw std::runtime_error( - "ERROR: Box constraint ordering problem detected. Need to add input box constraints before " - "state box constraints."); - } + lqocProblem_->setInputBoxConstraints(nb_u_intermediate, + inputBoxConstraints_[settings_.nThreads]->getLowerBoundsIntermediate(), + inputBoxConstraints_[settings_.nThreads]->getUpperBoundsIntermediate(), u_sparsity_col_intermediate, + u_ff_); + } + } +} + +template +void NLOCBackendBase::setStateBoxConstraintsForLQOCProblem() +{ + if (stateBoxConstraints_[settings_.nThreads] != nullptr) + { + const int nb_x_intermediate = + stateBoxConstraints_[settings_.nThreads]->getJacobianStateNonZeroCountIntermediate(); - Eigen::VectorXi ux_sparsity_intermediate(nb_ux_intermediate); - // shift indices to match combined decision vector [u, x] - x_sparsity_col_intermediate.array() += CONTROL_DIM; - ux_sparsity_intermediate << u_sparsity_col_intermediate, x_sparsity_col_intermediate; + if (nb_x_intermediate > 0) + { + Eigen::VectorXi x_sparsity_row, x_sparsity_col_intermediate; + + stateBoxConstraints_[settings_.nThreads]->sparsityPatternStateIntermediate( + x_sparsity_row, x_sparsity_col_intermediate); - lqocProblem_->setIntermediateBoxConstraints(nb_ux_intermediate, - boxConstraints_[settings_.nThreads]->getLowerBoundsIntermediate(), - boxConstraints_[settings_.nThreads]->getUpperBoundsIntermediate(), ux_sparsity_intermediate); + lqocProblem_->setIntermediateStateBoxConstraints(nb_x_intermediate, + stateBoxConstraints_[settings_.nThreads]->getLowerBoundsIntermediate(), + stateBoxConstraints_[settings_.nThreads]->getUpperBoundsIntermediate(), x_sparsity_col_intermediate, + x_); } - // terminal box constraints - const int nb_x_terminal = boxConstraints_[settings_.nThreads]->getJacobianStateNonZeroCountTerminal(); + // check number of terminal box constraints + const int nb_x_terminal = stateBoxConstraints_[settings_.nThreads]->getJacobianStateNonZeroCountTerminal(); if (nb_x_terminal > 0) { - boxConstraints_[settings_.nThreads]->sparsityPatternStateTerminal(x_sparsity_row, x_sparsity_col_terminal); + Eigen::VectorXi x_sparsity_row_terminal, x_sparsity_col_terminal; + + stateBoxConstraints_[settings_.nThreads]->sparsityPatternStateTerminal( + x_sparsity_row_terminal, x_sparsity_col_terminal); lqocProblem_->setTerminalBoxConstraints(nb_x_terminal, - boxConstraints_[settings_.nThreads]->getLowerBoundsTerminal(), - boxConstraints_[settings_.nThreads]->getUpperBoundsTerminal(), x_sparsity_col_terminal); + stateBoxConstraints_[settings_.nThreads]->getLowerBoundsTerminal(), + stateBoxConstraints_[settings_.nThreads]->getUpperBoundsTerminal(), x_sparsity_col_terminal, x_.back()); } } } @@ -758,11 +809,9 @@ void NLOCBackendBase:: Eigen::Matrix g_eval = generalConstraints_[threadId]->evaluateIntermediate(); - // rewrite constraint boundaries in absolute coordinates as required by LQOC problem - p.d_lb_[k] = generalConstraints_[threadId]->getLowerBoundsIntermediate() - g_eval + p.C_[k] * x_[k] + - p.D_[k] * u_ff_[k]; - p.d_ub_[k] = generalConstraints_[threadId]->getUpperBoundsIntermediate() - g_eval + p.C_[k] * x_[k] + - p.D_[k] * u_ff_[k]; + // rewrite constraint boundaries in relative coordinates as required by LQOC problem + p.d_lb_[k] = generalConstraints_[threadId]->getLowerBoundsIntermediate() - g_eval; + p.d_ub_[k] = generalConstraints_[threadId]->getUpperBoundsIntermediate() - g_eval; } } } @@ -777,12 +826,9 @@ void NLOCBackendBase:: // derivative of terminal cost with respect to state p.Q_[K_] = costFunctions_[settings_.nThreads]->stateSecondDerivativeTerminal(); - p.qv_[K_] = costFunctions_[settings_.nThreads]->stateDerivativeTerminal() - p.Q_[K_] * x_[K_]; + p.qv_[K_] = costFunctions_[settings_.nThreads]->stateDerivativeTerminal(); // p.q_[K_] = ... // omitted since not needed in GNMS/ILQR -- WARNING, potentially implement when using a different QP solver - // set terminal reference state - p.x_[K_] = x_[K_]; - // init terminal general constraints, if any if (generalConstraints_[settings_.nThreads] != nullptr) { @@ -796,10 +842,8 @@ void NLOCBackendBase:: Eigen::Matrix g_eval = generalConstraints_[settings_.nThreads]->evaluateTerminal(); - p.d_lb_[K_] = - generalConstraints_[settings_.nThreads]->getLowerBoundsTerminal() - g_eval + p.C_[K_] * x_[K_]; - p.d_ub_[K_] = - generalConstraints_[settings_.nThreads]->getUpperBoundsTerminal() - g_eval + p.C_[K_] * x_[K_]; + p.d_lb_[K_] = generalConstraints_[settings_.nThreads]->getLowerBoundsTerminal() - g_eval; + p.d_ub_[K_] = generalConstraints_[settings_.nThreads]->getUpperBoundsTerminal() - g_eval; } } } @@ -974,10 +1018,8 @@ bool NLOCBackendBase:: u_ff_prev_ = u_ff_; x_prev_ = x_; - // get feedback from lqoc solver which is always the same - getFeedback(); - if (!settings_.lineSearchSettings.active) // do full step updates + if (settings_.lineSearchSettings.type == LineSearchSettings::TYPE::NONE) // do full step updates { // lowest cost is cost of last rollout lowestCostPrevious = intermediateCostBest_ + finalCostBest_; @@ -1066,8 +1108,6 @@ bool NLOCBackendBase:: template void NLOCBackendBase::executeLineSearch(const size_t threadId, const scalar_t alpha, - const ControlVectorArray& u_ff_new, - const StateVectorArray& x_new, ct::core::StateVectorArray& x_alpha, ct::core::StateVectorArray& x_shot_alpha, ct::core::StateVectorArray& defects_recorded, @@ -1091,19 +1131,21 @@ void NLOCBackendBase:: return; // update feedforward with weighting alpha - u_alpha = u_ff_new * alpha + u_ff_prev_ * (1 - alpha); + u_alpha = delta_u_ff_ * alpha + u_ff_prev_; // update state decision variables with weighting alpha - x_alpha = x_new * alpha + x_prev_ * (1 - alpha); + x_alpha = delta_x_ * alpha + x_prev_; + // update x_lqr reference + ct::core::StateVectorArray x_ref_lqr = delta_x_ref_lqr_ * alpha + x_prev_; if (terminationFlag && *terminationFlag) return; bool dynamicsGood; - dynamicsGood = rolloutShotsSingleThreaded(threadId, 0, K_ - 1, u_alpha, x_alpha, x_alpha, x_shot_alpha, - defects_recorded, substepsX, substepsU, terminationFlag); + dynamicsGood = rolloutShotsSingleThreaded(threadId, 0 /*first index*/, K_ - 1 /*last index*/, u_alpha, x_alpha, + x_ref_lqr, x_shot_alpha, defects_recorded, substepsX, substepsU, terminationFlag); if (terminationFlag && *terminationFlag) return; @@ -1123,7 +1165,7 @@ void NLOCBackendBase:: return; // compute constraint violations specific to this alpha - if (boxConstraints_[threadId] != nullptr) + if ((inputBoxConstraints_[threadId] != nullptr) | (stateBoxConstraints_[threadId] != nullptr)) computeBoxConstraintErrorOfTrajectory(threadId, x_alpha, u_alpha, e_box_norm); if (terminationFlag && *terminationFlag) @@ -1143,15 +1185,106 @@ void NLOCBackendBase:: } +template +bool NLOCBackendBase::acceptStep(const SCALAR alpha, + const SCALAR intermediateCost, + const SCALAR finalCost, + const SCALAR defectNorm, + const SCALAR e_box_norm, + const SCALAR e_gen_norm, + const SCALAR lowestMeritPrevious, + SCALAR& new_merit) +{ + switch (settings_.lineSearchSettings.type) + { + case LineSearchSettings::TYPE::SIMPLE: + { + new_merit = intermediateCost + finalCost + settings_.meritFunctionRho * defectNorm + + settings_.meritFunctionRhoConstraints * (e_box_norm + e_gen_norm); + + if ((lowestMeritPrevious - new_merit > 0.0) && !std::isnan(new_merit)) + { + return true; + } + + break; + } + case LineSearchSettings::TYPE::ARMIJO: + { + new_merit = intermediateCost + finalCost + settings_.meritFunctionRho * defectNorm + + settings_.meritFunctionRhoConstraints * (e_box_norm + e_gen_norm); + + if (std::isnan(new_merit)) + return false; + + const ControlVectorArray& lv = lqocSolver_->get_lv(); + + SCALAR Delta1 = 0; + SCALAR Delta2 = 0; + for (int i = 0; i < K_; i++) + { + // the expected decrease can sometimes become negative and allow an overall increase of cost - account for that below + Delta1 += (lv[i].transpose() * lqocProblem_->rv_[i])(0); + Delta2 += (lv[i].transpose() * lqocProblem_->R_[i] * lv[i])(0); + } + + SCALAR expCostDecr = alpha * (Delta1 + alpha * 0.5 * Delta2); + + if ((lowestMeritPrevious - new_merit) >= (settings_.lineSearchSettings.armijo_parameter * expCostDecr) && + ((lowestMeritPrevious - new_merit) >= 0.0)) + { + return true; + } + + break; + } + case LineSearchSettings::TYPE::GOLDSTEIN: + { + throw std::runtime_error("Goldstein conditions not completed yet, use Armijo for now."); + + new_merit = intermediateCost + finalCost + settings_.meritFunctionRho * defectNorm + + settings_.meritFunctionRhoConstraints * (e_box_norm + e_gen_norm); + + if (std::isnan(new_merit)) + return false; + + const ControlVectorArray& lv = lqocSolver_->get_lv(); + + SCALAR Delta1 = 0; + SCALAR Delta2 = 0; + for (int i = 0; i < K_; i++) + { + // the expected decrease can sometimes become negative and allow an overall increase of cost - account for that below + Delta1 += (lv[i].transpose() * lqocProblem_->rv_[i])(0); + Delta2 += (lv[i].transpose() * lqocProblem_->R_[i] * lv[i])(0); + } + + SCALAR expCostDecr = alpha * (Delta1 + alpha * 0.5 * Delta2); + + if (((lowestMeritPrevious - new_merit) >= (settings_.lineSearchSettings.armijo_parameter * expCostDecr)) && + ((lowestMeritPrevious - new_merit) <= + ((1 - settings_.lineSearchSettings.armijo_parameter) * expCostDecr))) + { + return true; + } + + break; + } + default: + throw std::runtime_error("Invalid line search type in acceptStep()"); + }; + + return false; +} + + template void NLOCBackendBase::prepareSolveLQProblem(size_t startIndex) { lqpCounter_++; // if solver is HPIPM, there's nothing to prepare - if (settings_.lqocp_solver == Settings_t::LQOCP_SOLVER::HPIPM_SOLVER) - { - } + if (settings_.lqocp_solver == Settings_t::LQOCP_SOLVER::HPIPM_SOLVER) {} // if solver is GNRiccati - we iterate backward up to the first stage else if (settings_.lqocp_solver == Settings_t::LQOCP_SOLVER::GNRICCATI_SOLVER) { @@ -1183,7 +1316,7 @@ void NLOCBackendBase:: for (int i = endIndex; i >= 0; i--) lqocSolver_->solveSingleStage(i); - lqocSolver_->extractLQSolution(); + lqocSolver_->computeStatesAndControls(); } else throw std::runtime_error("unknown solver type in finishSolveLQProblem()"); @@ -1195,12 +1328,19 @@ void NLOCBackendBase:: { lqpCounter_++; - if (lqocProblem_->isBoxConstrained()) + if (lqocProblem_->isInputBoxConstrained()) + { + if (settings_.debugPrint) + std::cout << "LQ Problem has input box constraints. Configuring box constraints now. " << std::endl; + + lqocSolver_->configureInputBoxConstraints(lqocProblem_); + } + if (lqocProblem_->isStateBoxConstrained()) { if (settings_.debugPrint) - std::cout << "LQ Problem has box constraints. Configuring box constraints now. " << std::endl; + std::cout << "LQ Problem has state box constraints. Configuring box constraints now. " << std::endl; - lqocSolver_->configureBoxConstraints(lqocProblem_); + lqocSolver_->configureStateBoxConstraints(lqocProblem_); } if (lqocProblem_->isGeneralConstrained()) { @@ -1259,12 +1399,79 @@ void NLOCBackendBase:: template -void NLOCBackendBase::doFullStepUpdate() +void NLOCBackendBase::extractSolution() { - u_ff_ = lqocSolver_->getSolutionControl(); - x_ = lqocSolver_->getSolutionState(); + L_.setConstant(core::FeedbackMatrix::Zero()); // TODO should eventually go away + x_ref_lqr_ = x_; + // extract the quantities required to update the solution candidate, depending on solver settings + /* + * case: GNMS: compute and retrieve dx, du + * case: GNMS(M): compute and retrieve dx, du + * case: Classical (open-loop) Single Shooting: compute and retrieve dx, du; + * case: iLQR: compute and retrieve lv, L + * case: Multiple-Shooting-iLQR: compute and retrieve dx, lv, L + * case: Closed-loop Single Shooting: compute and retrieve dx, du, L + * case: Closed-loop GNMS(M): compute and retrieve dx, du, L + */ + switch (settings_.nlocp_algorithm) + { + case NLOptConSettings::NLOCP_ALGORITHM::GNMS: + case NLOptConSettings::NLOCP_ALGORITHM::GNMS_M_OL: + case NLOptConSettings::NLOCP_ALGORITHM::SS_OL: + { + lqocSolver_->computeStatesAndControls(); + delta_u_ff_ = lqocSolver_->getSolutionControl(); + delta_x_ = lqocSolver_->getSolutionState(); + delta_x_ref_lqr_.setConstant(ct::core::StateVector::Zero()); + break; + } + case NLOptConSettings::NLOCP_ALGORITHM::ILQR: + { + lqocSolver_->compute_lv(); + delta_u_ff_ = lqocSolver_->get_lv(); + lqocSolver_->computeFeedbackMatrices(); + L_ = lqocSolver_->getSolutionFeedback(); + delta_x_.setConstant(ct::core::StateVector::Zero()); + delta_x_ref_lqr_.setConstant(ct::core::StateVector::Zero()); + break; + } + case NLOptConSettings::NLOCP_ALGORITHM::MS_ILQR: + { + lqocSolver_->computeStatesAndControls(); + delta_x_ = lqocSolver_->getSolutionState(); + delta_x_ref_lqr_.setConstant(ct::core::StateVector::Zero()); + lqocSolver_->compute_lv(); + delta_u_ff_ = lqocSolver_->get_lv(); + lqocSolver_->computeFeedbackMatrices(); + L_ = lqocSolver_->getSolutionFeedback(); + break; + } + case NLOptConSettings::NLOCP_ALGORITHM::SS_CL: + case NLOptConSettings::NLOCP_ALGORITHM::GNMS_M_CL: + { + lqocSolver_->computeStatesAndControls(); + delta_u_ff_ = lqocSolver_->getSolutionControl(); + delta_x_ = lqocSolver_->getSolutionState(); + delta_x_ref_lqr_ = delta_x_; + lqocSolver_->computeFeedbackMatrices(); + L_ = lqocSolver_->getSolutionFeedback(); + break; + } + default: + throw std::runtime_error("Unknown NLOC Algorithm type given in settings."); + } +} + + +template +void NLOCBackendBase::doFullStepUpdate() +{ alphaBest_ = 1.0; + + x_ += delta_x_; + u_ff_ += delta_u_ff_; + x_ref_lqr_ += delta_x_ref_lqr_; } template @@ -1282,16 +1489,6 @@ NLOCBackendBase::getSu return summaryAllIterations_; } -template -void NLOCBackendBase::getFeedback() -{ - if (settings_.closedLoopShooting) - L_ = lqocSolver_->getSolutionFeedback(); - else - L_.setConstant(core::FeedbackMatrix::Zero()); // TODO should eventually go away -} - - template void NLOCBackendBase::resetDefects() { @@ -1417,18 +1614,35 @@ NLOCBackendBase::getCo template std::vector::OptConProblem_t:: ConstraintPtr_t>& -NLOCBackendBase::getBoxConstraintsInstances() +NLOCBackendBase::getInputBoxConstraintsInstances() +{ + return inputBoxConstraints_; +} + + +template +const std::vector::OptConProblem_t:: + ConstraintPtr_t>& +NLOCBackendBase::getInputBoxConstraintsInstances() const +{ + return inputBoxConstraints_; +} + +template +std::vector::OptConProblem_t:: + ConstraintPtr_t>& +NLOCBackendBase::getStateBoxConstraintsInstances() { - return boxConstraints_; + return inputBoxConstraints_; } template const std::vector::OptConProblem_t:: ConstraintPtr_t>& -NLOCBackendBase::getBoxConstraintsInstances() const +NLOCBackendBase::getStateBoxConstraintsInstances() const { - return boxConstraints_; + return stateBoxConstraints_; } @@ -1462,20 +1676,15 @@ int NLOCBackendBase::g return K_; } - template int NLOCBackendBase::getNumStepsPerShot() const { - // todo try to find clear solution here - if (settings_.nlocp_algorithm == NLOptConSettings::NLOCP_ALGORITHM::ILQR) + if (settings_.isSingleShooting()) return K_; - else if (settings_.nlocp_algorithm == NLOptConSettings::NLOCP_ALGORITHM::GNMS) - return settings_.K_shot; else - throw std::runtime_error("Unknown algorithm type in NLOCBackendBase::getNumStepsPerShot()"); + return settings_.K_shot; } - template const typename NLOCBackendBase::Settings_t& NLOCBackendBase::getSettings() const diff --git a/ct_optcon/include/ct/optcon/nloc/NLOCBackendBase.hpp b/ct_optcon/include/ct/optcon/nloc/NLOCBackendBase.hpp index 38c63e70d..7726909d5 100644 --- a/ct_optcon/include/ct/optcon/nloc/NLOCBackendBase.hpp +++ b/ct_optcon/include/ct/optcon/nloc/NLOCBackendBase.hpp @@ -174,9 +174,14 @@ class NLOCBackendBase void changeLinearSystem(const typename OptConProblem_t::LinearPtr_t& lin); /*! - * \brief Change the box constraints + * \brief Change the input box constraints */ - void changeBoxConstraints(const typename OptConProblem_t::ConstraintPtr_t& con); + void changeInputBoxConstraints(const typename OptConProblem_t::ConstraintPtr_t& con); + + /*! + * \brief Change the state box constraints + */ + void changeStateBoxConstraints(const typename OptConProblem_t::ConstraintPtr_t& con); /*! * \brief Change the general constraints @@ -232,9 +237,11 @@ class NLOCBackendBase * * @return The box constraint instances */ - std::vector& getBoxConstraintsInstances(); + std::vector& getInputBoxConstraintsInstances(); + std::vector& getStateBoxConstraintsInstances(); - const std::vector& getBoxConstraintsInstances() const; + const std::vector& getInputBoxConstraintsInstances() const; + const std::vector& getStateBoxConstraintsInstances() const; /** * @brief Direct accessor to the general constraints @@ -301,7 +308,6 @@ class NLOCBackendBase */ virtual void prepareSolveLQProblem(size_t startIndex); - virtual void finishSolveLQProblem(size_t endIndex); /*! @@ -309,6 +315,12 @@ class NLOCBackendBase */ virtual void solveFullLQProblem(); + /** + * @brief extract relevant quantities for the following rollout/solution update step from the LQ solver + * @note not all algorithms require all data updates, hence the separation. + */ + void extractSolution(); + //! compute costs of solution candidate void updateCosts(); @@ -335,10 +347,8 @@ class NLOCBackendBase virtual void computeLQApproximation(size_t firstIndex, size_t lastIndex) = 0; //! sets the box constraints for the entire time horizon including terminal stage - void setBoxConstraintsForLQOCProblem(); - - //! obtain feedback update from lqoc solver, if provided - void getFeedback(); + void setInputBoxConstraintsForLQOCProblem(); + void setStateBoxConstraintsForLQOCProblem(); //! reset all defects to zero void resetDefects(); @@ -400,7 +410,7 @@ class NLOCBackendBase //! Computes the linearized Dynamics and quadratic cost approximation at a specific point of the trajectory /*! - This function calculates the affine dynamics approximation, i.e. matrices A, B and b in \f$ x_{n+1} = A_n x_n + B_n u_n + b_n \f$ + This function calculates the affine dynamics approximation, i.e. matrices A, B and b in \f$ \delta x_{n+1} = A_n \delta x_n + B_n \delta u_n + b_n \f$ at a specific point of the trajectory. This function also calculates the quadratic costs as provided by the costFunction pointer. and maps it into the coordinates of the LQ problem. @@ -412,7 +422,7 @@ class NLOCBackendBase //! Computes the linearized general constraints at a specific point of the trajectory /*! - This function calculates the linearization, i.e. matrices d, C and D in \f$ d_{lb} \leq C x + D u \leq d_{ub}\f$ + This function calculates the linearization, i.e. matrices d, C and D in \f$ d_{lb} \leq C \delta x + D \delta u \leq d_{ub}\f$ at a specific point of the trajectory \param threadId the id of the worker thread @@ -490,8 +500,6 @@ class NLOCBackendBase //! Check if controller with particular alpha is better void executeLineSearch(const size_t threadId, const scalar_t alpha, - const ControlVectorArray& u_ff_new, - const StateVectorArray& x_new, ct::core::StateVectorArray& x_recorded, ct::core::StateVectorArray& x_shot_recorded, ct::core::StateVectorArray& defects_recorded, @@ -506,6 +514,17 @@ class NLOCBackendBase std::atomic_bool* terminationFlag = nullptr) const; + //! in case of line-search compute new merit and check if to accept step. Returns true if accept step + bool acceptStep( + const SCALAR alpha, + const SCALAR intermediateCost, + const SCALAR finalCost, + const SCALAR defectNorm, + const SCALAR e_box_norm, + const SCALAR e_gen_norm, + const SCALAR lowestMeritPrevious, + SCALAR& new_merit); + //! Update feedforward controller /*! * This function updates the feedforward Controller based on the previous calculation. @@ -530,30 +549,33 @@ class NLOCBackendBase template SCALAR computeDefectsNorm(const StateVectorArray& d) const; - //! The policy. currently only for returning the result, should eventually replace L_ and u_ff_ (todo) - NLOCBackendBase::Policy_t policy_; - - ct::core::tpl::TimeArray t_; //! the time trajectory - bool initialized_; bool configured_; size_t iteration_; /*!< current iteration */ - Settings_t settings_; + bool firstRollout_; - int K_; //! the number of stages in the overall OptConProblem + Settings_t settings_; - StateVectorArray x_; - StateVectorArray xShot_; - StateVectorArray x_prev_; + int K_; //! the number of stages in the overall OptConProblem + ct::core::tpl::TimeArray t_; //! the time trajectory + StateVectorArray x_; //! state array variables + StateVectorArray xShot_; //! rolled-out state (at the end of a time step forward) + StateVectorArray d_; //! defects in between end of rollouts and subsequent state decision vars + StateVectorArray x_prev_; //! state array from previous iteration + StateVectorArray x_ref_lqr_; //! reference for lqr - ControlVectorArray u_ff_; - ControlVectorArray u_ff_prev_; + ControlVectorArray u_ff_; //! feed forward controls + ControlVectorArray u_ff_prev_; //! feed forward controls from previous iteration + FeedbackArray L_; //! time-varying lqr feedback - StateVectorArray d_; /*!< defects */ + ControlVectorArray delta_u_ff_; //! pointer to control increment + StateVectorArray delta_x_; //! pointer to state increment + StateVectorArray delta_x_ref_lqr_; //! state array from previous iteration - FeedbackArray L_; + StateSubstepsPtr substepsX_; //! state substeps recorded by integrator during rollouts + ControlSubstepsPtr substepsU_; //! control substeps recorded by integrator during rollouts SCALAR d_norm_; //! sum of the norms of all defects (internal constraint) SCALAR e_box_norm_; //! sum of the norms of all box constraint violations @@ -561,18 +583,6 @@ class NLOCBackendBase SCALAR lx_norm_; //! sum of the norms of state update SCALAR lu_norm_; //! sum of the norms of control update - //! shared pointer to the linear-quadratic optimal control problem - std::shared_ptr> lqocProblem_; - - //! shared pointer to the linear-quadratic optimal control solver - std::shared_ptr> lqocSolver_; - - StateSubstepsPtr substepsX_; - ControlSubstepsPtr substepsU_; - - //! pointer to instance of the system interface - systemInterfacePtr_t systemInterface_; - scalar_t intermediateCostBest_; scalar_t finalCostBest_; scalar_t lowestCost_; @@ -581,29 +591,38 @@ class NLOCBackendBase scalar_t intermediateCostPrevious_; scalar_t finalCostPrevious_; + scalar_t alphaBest_; -//! if building with MATLAB support, include matfile -#ifdef MATLAB - matlab::MatFile matFile_; -#endif //MATLAB + //! shared pointer to the linear-quadratic optimal control problem that is constructed by NLOC + std::shared_ptr> lqocProblem_; + + //! shared pointer to the linear-quadratic optimal control solver, that solves above LQOCP + std::shared_ptr> lqocSolver_; + //! pointer to instance of the system interface + systemInterfacePtr_t systemInterface_; /*! * of the following objects, we have nThreads+1 instantiations in form of a vector. * Every instantiation is dedicated to a certain thread in the multi-thread implementation */ std::vector costFunctions_; - std::vector boxConstraints_; + std::vector inputBoxConstraints_; + std::vector stateBoxConstraints_; std::vector generalConstraints_; - - bool firstRollout_; - scalar_t alphaBest_; - //! a counter used to identify lqp problems in derived classes, i.e. for thread management in MP size_t lqpCounter_; + //! The policy. currently only for returning the result, should eventually replace L_ and u_ff_ (todo) + NLOCBackendBase::Policy_t policy_; + SummaryAllIterations summaryAllIterations_; + + //! if building with MATLAB support, include matfile +#ifdef MATLAB + matlab::MatFile matFile_; +#endif //MATLAB }; diff --git a/ct_optcon/include/ct/optcon/nloc/NLOCBackendMP-impl.hpp b/ct_optcon/include/ct/optcon/nloc/NLOCBackendMP-impl.hpp index 59ca2d380..45f183f2b 100644 --- a/ct_optcon/include/ct/optcon/nloc/NLOCBackendMP-impl.hpp +++ b/ct_optcon/include/ct/optcon/nloc/NLOCBackendMP-impl.hpp @@ -323,8 +323,8 @@ void NLOCBackendMP::ro ". Not waking up workers."); #endif //DEBUG_PRINT_MP - this->rolloutSingleShot(this->settings_.nThreads, firstIndex, this->u_ff_, this->x_, this->x_, this->xShot_, - *this->substepsX_, *this->substepsU_); + this->rolloutSingleShot(this->settings_.nThreads, firstIndex, this->u_ff_, this->x_, this->x_ref_lqr_, + this->xShot_, *this->substepsX_, *this->substepsU_); this->computeSingleDefect(firstIndex, this->x_, this->xShot_, this->d_); return; @@ -394,8 +394,8 @@ void NLOCBackendMP::ro std::to_string(KMax_ - k)); #endif - this->rolloutSingleShot( - threadId, kShot, this->u_ff_, this->x_, this->x_, this->xShot_, *this->substepsX_, *this->substepsU_); + this->rolloutSingleShot(threadId, kShot, this->u_ff_, this->x_, this->x_ref_lqr_, this->xShot_, + *this->substepsX_, *this->substepsU_); this->computeSingleDefect(kShot, this->x_, this->xShot_, this->d_); } @@ -498,16 +498,16 @@ void NLOCBackendMP::li typename Base::ControlSubstepsPtr substepsU = typename Base::ControlSubstepsPtr(new typename Base::ControlSubsteps(this->K_ + 1)); - this->executeLineSearch(threadId, alpha, this->lqocSolver_->getSolutionControl(), - this->lqocSolver_->getSolutionState(), x_search, x_shot_search, defects_recorded, u_recorded, + this->executeLineSearch(threadId, alpha, x_search, x_shot_search, defects_recorded, u_recorded, intermediateCost, finalCost, defectNorm, e_box_norm, e_gen_norm, *substepsX, *substepsU, &alphaBestFound_); - // compute merit - cost = intermediateCost + finalCost + this->settings_.meritFunctionRho * defectNorm + - this->settings_.meritFunctionRhoConstraints * (e_box_norm + e_gen_norm); - lineSearchResultMutex_.lock(); - if (cost < lowestCostPrevious_ && !std::isnan(cost)) + + // check for step acceptance and get new merit/cost + bool stepAccepted = + this->acceptStep(alpha, intermediateCost, finalCost, defectNorm, e_box_norm, e_gen_norm, lowestCostPrevious_, cost); + + if (stepAccepted) { // make sure we do not alter an existing result if (alphaBestFound_) @@ -518,8 +518,8 @@ void NLOCBackendMP::li if (this->settings_.lineSearchSettings.debugPrint) { - printString("[LineSearch, Thread " + std::to_string(threadId) + "]: Lower cost/merit found at alpha:" + - std::to_string(alpha)); + printString("[LineSearch, Thread " + std::to_string(threadId) + + "]: Lower cost/merit found at alpha:" + std::to_string(alpha)); printString("[LineSearch]: Cost:\t" + std::to_string(intermediateCost + finalCost)); printString("[LineSearch]: Defect:\t" + std::to_string(defectNorm)); printString("[LineSearch]: err box constr:\t" + std::to_string(e_box_norm)); diff --git a/ct_optcon/include/ct/optcon/nloc/NLOCBackendMP.hpp b/ct_optcon/include/ct/optcon/nloc/NLOCBackendMP.hpp index d18b34231..8d2d4052c 100644 --- a/ct_optcon/include/ct/optcon/nloc/NLOCBackendMP.hpp +++ b/ct_optcon/include/ct/optcon/nloc/NLOCBackendMP.hpp @@ -28,7 +28,7 @@ template -class NLOCBackendMP : public NLOCBackendBase +class NLOCBackendMP final : public NLOCBackendBase { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/ct_optcon/include/ct/optcon/nloc/NLOCBackendST-impl.hpp b/ct_optcon/include/ct/optcon/nloc/NLOCBackendST-impl.hpp index ed299b00f..925de1a8e 100644 --- a/ct_optcon/include/ct/optcon/nloc/NLOCBackendST-impl.hpp +++ b/ct_optcon/include/ct/optcon/nloc/NLOCBackendST-impl.hpp @@ -58,7 +58,7 @@ void NLOCBackendST::ro for (size_t k = firstIndex; k <= lastIndex; k = k + this->getNumStepsPerShot()) { // rollout the shot - this->rolloutSingleShot(this->settings_.nThreads, k, this->u_ff_, this->x_, this->x_, this->xShot_, + this->rolloutSingleShot(this->settings_.nThreads, k, this->u_ff_, this->x_, this->x_ref_lqr_, this->xShot_, *this->substepsX_, *this->substepsU_); this->computeSingleDefect(k, this->x_, this->xShot_, this->d_); @@ -105,18 +105,15 @@ SCALAR NLOCBackendST:: typename Base::ControlSubstepsPtr(new typename Base::ControlSubsteps(this->K_ + 1)); - this->executeLineSearch(this->settings_.nThreads, alpha, this->lqocSolver_->getSolutionControl(), - this->lqocSolver_->getSolutionState(), x_search, x_shot_search, defects_recorded, u_recorded, + this->executeLineSearch(this->settings_.nThreads, alpha, x_search, x_shot_search, defects_recorded, u_recorded, intermediateCost, finalCost, defectNorm, e_box_norm, e_gen_norm, *substepsX, *substepsU); - - // compute merit - cost = intermediateCost + finalCost + this->settings_.meritFunctionRho * defectNorm + - this->settings_.meritFunctionRhoConstraints * (e_box_norm + e_gen_norm); + // compute new merit and check for step acceptance + bool stepAccepted = + this->acceptStep(alpha, intermediateCost, finalCost, defectNorm, e_box_norm, e_gen_norm, this->lowestCost_, cost); // catch the case that a rollout might be unstable - if (std::isnan(cost) || - cost >= this->lowestCost_) // TODO: alternatively cost >= (this->lowestCost_*(1 - 1e-3*alpha)), study this + if (!stepAccepted) { if (this->settings_.lineSearchSettings.debugPrint) { @@ -133,7 +130,7 @@ SCALAR NLOCBackendST:: } else { - // cost < this->lowestCost_ , better merit/cost found! + // step accepted if (this->settings_.lineSearchSettings.debugPrint) { diff --git a/ct_optcon/include/ct/optcon/nloc/NLOCBackendST.hpp b/ct_optcon/include/ct/optcon/nloc/NLOCBackendST.hpp index a6e38bc46..37b80c774 100644 --- a/ct_optcon/include/ct/optcon/nloc/NLOCBackendST.hpp +++ b/ct_optcon/include/ct/optcon/nloc/NLOCBackendST.hpp @@ -22,7 +22,7 @@ template -class NLOCBackendST : public NLOCBackendBase +class NLOCBackendST final : public NLOCBackendBase { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/ct_optcon/include/ct/optcon/nloc/algorithms/gnms/GNMS-impl.hpp b/ct_optcon/include/ct/optcon/nloc/algorithms/MultipleShooting-impl.hpp similarity index 72% rename from ct_optcon/include/ct/optcon/nloc/algorithms/gnms/GNMS-impl.hpp rename to ct_optcon/include/ct/optcon/nloc/algorithms/MultipleShooting-impl.hpp index 99282c9b6..825016ddf 100644 --- a/ct_optcon/include/ct/optcon/nloc/algorithms/gnms/GNMS-impl.hpp +++ b/ct_optcon/include/ct/optcon/nloc/algorithms/MultipleShooting-impl.hpp @@ -9,31 +9,26 @@ namespace ct { namespace optcon { template -GNMS::GNMS(std::shared_ptr& backend_, +MultipleShooting::MultipleShooting(std::shared_ptr& backend_, const Settings_t& settings) : Base(backend_) { } template -GNMS::~GNMS() -{ -} - -template -void GNMS::configure(const Settings_t& settings) +void MultipleShooting::configure(const Settings_t& settings) { this->backend_->configure(settings); } template -void GNMS::setInitialGuess(const Policy_t& initialGuess) +void MultipleShooting::setInitialGuess(const Policy_t& initialGuess) { this->backend_->setInitialGuess(initialGuess); } template -bool GNMS::runIteration() +bool MultipleShooting::runIteration() { prepareIteration(); @@ -41,17 +36,17 @@ bool GNMS::runIteratio } template -void GNMS::prepareIteration() +void MultipleShooting::prepareIteration() { bool debugPrint = this->backend_->getSettings().debugPrint; auto startPrepare = std::chrono::steady_clock::now(); if (!this->backend_->isInitialized()) - throw std::runtime_error("GNMS is not initialized!"); + throw std::runtime_error("MultipleShooting is not initialized!"); if (!this->backend_->isConfigured()) - throw std::runtime_error("GNMS is not configured!"); + throw std::runtime_error("MultipleShooting is not configured!"); this->backend_->checkProblem(); @@ -65,35 +60,36 @@ void GNMS::prepareIter } auto start = std::chrono::steady_clock::now(); - this->backend_->setBoxConstraintsForLQOCProblem(); + this->backend_->setInputBoxConstraintsForLQOCProblem(); + this->backend_->setStateBoxConstraintsForLQOCProblem(); this->backend_->computeLQApproximation(K_shot, K - 1); auto end = std::chrono::steady_clock::now(); auto diff = end - start; if (debugPrint) - std::cout << "[GNMS]: computing LQ Approximation from index " << K_shot << " to N-1 took " + std::cout << "[MultipleShooting]: computing LQ Approximation from index " << K_shot << " to N-1 took " << std::chrono::duration(diff).count() << " ms" << std::endl; if (debugPrint) - std::cout << "[GNMS]: Solving prepare stage of LQOC Problem" << std::endl; + std::cout << "[MultipleShooting]: Solving prepare stage of LQOC Problem" << std::endl; start = std::chrono::steady_clock::now(); this->backend_->prepareSolveLQProblem(K_shot); end = std::chrono::steady_clock::now(); diff = end - start; if (debugPrint) - std::cout << "[GNMS]: Prepare phase of LQOC problem took " + std::cout << "[MultipleShooting]: Prepare phase of LQOC problem took " << std::chrono::duration(diff).count() << " ms" << std::endl; auto endPrepare = std::chrono::steady_clock::now(); if (debugPrint) - std::cout << "[GNMS]: prepareIteration() took " + std::cout << "[MultipleShooting]: prepareIteration() took " << std::chrono::duration(endPrepare - startPrepare).count() << " ms" << std::endl; } //! prepareIteration() template -bool GNMS::finishIteration() +bool MultipleShooting::finishIteration() { int K_shot = this->backend_->getNumStepsPerShot(); @@ -119,18 +115,19 @@ bool GNMS::finishItera auto end = std::chrono::steady_clock::now(); auto diff = end - start; if (debugPrint) - std::cout << "[GNMS]: computing LQ approximation for first multiple-shooting interval took " + std::cout << "[MultipleShooting]: computing LQ approximation for first multiple-shooting interval took " << std::chrono::duration(diff).count() << " ms" << std::endl; if (debugPrint) - std::cout << "[GNMS]: Finish phase LQOC Problem" << std::endl; + std::cout << "[MultipleShooting]: Finish phase LQOC Problem" << std::endl; start = std::chrono::steady_clock::now(); this->backend_->finishSolveLQProblem(K_shot - 1); + this->backend_->extractSolution(); end = std::chrono::steady_clock::now(); diff = end - start; if (debugPrint) - std::cout << "[GNMS]: Finish solving LQOC problem took " + std::cout << "[MultipleShooting]: Finish solving LQOC problem took " << std::chrono::duration(diff).count() << " ms" << std::endl; start = std::chrono::steady_clock::now(); @@ -138,14 +135,14 @@ bool GNMS::finishItera end = std::chrono::steady_clock::now(); diff = end - start; if (debugPrint) - std::cout << "[GNMS]: Line search took " << std::chrono::duration(diff).count() << " ms" + std::cout << "[MultipleShooting]: Line search took " << std::chrono::duration(diff).count() << " ms" << std::endl; if (debugPrint) { auto endFinish = std::chrono::steady_clock::now(); - std::cout << "[GNMS]: finishIteration() took " + std::cout << "[MultipleShooting]: finishIteration() took " << std::chrono::duration(endFinish - startFinish).count() << " ms" << std::endl; } @@ -164,17 +161,17 @@ bool GNMS::finishItera template -void GNMS::prepareMPCIteration() +void MultipleShooting::prepareMPCIteration() { bool debugPrint = this->backend_->getSettings().debugPrint; auto startPrepare = std::chrono::steady_clock::now(); if (!this->backend_->isInitialized()) - throw std::runtime_error("GNMS is not initialized!"); + throw std::runtime_error("MultipleShooting is not initialized!"); if (!this->backend_->isConfigured()) - throw std::runtime_error("GNMS is not configured!"); + throw std::runtime_error("MultipleShooting is not configured!"); this->backend_->checkProblem(); @@ -186,29 +183,30 @@ void GNMS::prepareMPCI this->backend_->rolloutShots(K_shot, K - 1); auto start = std::chrono::steady_clock::now(); - this->backend_->setBoxConstraintsForLQOCProblem(); + this->backend_->setInputBoxConstraintsForLQOCProblem(); + this->backend_->setStateBoxConstraintsForLQOCProblem(); this->backend_->computeLQApproximation(K_shot, K - 1); auto end = std::chrono::steady_clock::now(); auto diff = end - start; if (debugPrint) - std::cout << "[GNMS-MPC]: computing LQ approximation from index " << K_shot << " to N-1 took " + std::cout << "[MultipleShooting-MPC]: computing LQ approximation from index " << K_shot << " to N-1 took " << std::chrono::duration(diff).count() << " ms" << std::endl; if (debugPrint) - std::cout << "[GNMS-MPC]: Solving prepare stage of LQOC Problem" << std::endl; + std::cout << "[MultipleShooting-MPC]: Solving prepare stage of LQOC Problem" << std::endl; start = std::chrono::steady_clock::now(); this->backend_->prepareSolveLQProblem(K_shot); end = std::chrono::steady_clock::now(); diff = end - start; if (debugPrint) - std::cout << "[GNMS-MPC]: Prepare phase of LQOC problem took " + std::cout << "[MultipleShooting-MPC]: Prepare phase of LQOC problem took " << std::chrono::duration(diff).count() << " ms" << std::endl; auto endPrepare = std::chrono::steady_clock::now(); if (debugPrint) - std::cout << "[GNMS-MPC]: prepareIteration() took " + std::cout << "[MultipleShooting-MPC]: prepareIteration() took " << std::chrono::duration(endPrepare - startPrepare).count() << " ms" << std::endl; @@ -216,7 +214,7 @@ void GNMS::prepareMPCI template -bool GNMS::finishMPCIteration() +bool MultipleShooting::finishMPCIteration() { int K_shot = this->backend_->getNumStepsPerShot(); @@ -240,18 +238,19 @@ bool GNMS::finishMPCIt auto end = std::chrono::steady_clock::now(); auto diff = end - start; if (debugPrint) - std::cout << "[GNMS-MPC]: computing LQ approximation for first multiple-shooting interval took " + std::cout << "[MultipleShooting-MPC]: computing LQ approximation for first multiple-shooting interval took " << std::chrono::duration(diff).count() << " ms" << std::endl; if (debugPrint) - std::cout << "[GNMS-MPC]: Finish phase LQOC Problem" << std::endl; + std::cout << "[MultipleShooting-MPC]: Finish phase LQOC Problem" << std::endl; start = std::chrono::steady_clock::now(); this->backend_->finishSolveLQProblem(K_shot - 1); + this->backend_->extractSolution(); end = std::chrono::steady_clock::now(); diff = end - start; if (debugPrint) - std::cout << "[GNMS-MPC]: Finish solving LQOC problem took " + std::cout << "[MultipleShooting-MPC]: Finish solving LQOC problem took " << std::chrono::duration(diff).count() << " ms" << std::endl; @@ -262,14 +261,14 @@ bool GNMS::finishMPCIt end = std::chrono::steady_clock::now(); diff = end - start; if (debugPrint) - std::cout << "[GNMS-MPC]: Solution update took " << std::chrono::duration(diff).count() + std::cout << "[MultipleShooting-MPC]: Solution update took " << std::chrono::duration(diff).count() << " ms" << std::endl; if (debugPrint) { auto endFinish = std::chrono::steady_clock::now(); - std::cout << "[GNMS-MPC]: finishIteration() took " + std::cout << "[MultipleShooting-MPC]: finishIteration() took " << std::chrono::duration(endFinish - startFinish).count() << " ms" << std::endl; } diff --git a/ct_optcon/include/ct/optcon/nloc/algorithms/gnms/GNMS.hpp b/ct_optcon/include/ct/optcon/nloc/algorithms/MultipleShooting.hpp similarity index 88% rename from ct_optcon/include/ct/optcon/nloc/algorithms/gnms/GNMS.hpp rename to ct_optcon/include/ct/optcon/nloc/algorithms/MultipleShooting.hpp index d4d1da60e..9acd65e98 100644 --- a/ct_optcon/include/ct/optcon/nloc/algorithms/gnms/GNMS.hpp +++ b/ct_optcon/include/ct/optcon/nloc/algorithms/MultipleShooting.hpp @@ -18,7 +18,7 @@ template -class GNMS : public NLOCAlgorithm +class MultipleShooting final : public NLOCAlgorithm { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -35,10 +35,10 @@ class GNMS : public NLOCAlgorithm& backend_, const Settings_t& settings); + MultipleShooting(std::shared_ptr& backend_, const Settings_t& settings); //! destructor - virtual ~GNMS(); + virtual ~MultipleShooting() = default; //! configure the solver virtual void configure(const Settings_t& settings) override; @@ -60,7 +60,7 @@ class GNMS : public NLOCAlgorithm -iLQR::iLQR(std::shared_ptr& backend_, +SingleShooting::SingleShooting( + std::shared_ptr& backend_, const Settings_t& settings) : Base(backend_) { } template -iLQR::~iLQR() -{ -} - -template -void iLQR::configure(const Settings_t& settings) +void SingleShooting::configure(const Settings_t& settings) { this->backend_->configure(settings); } template -void iLQR::setInitialGuess(const Policy_t& initialGuess) +void SingleShooting::setInitialGuess( + const Policy_t& initialGuess) { this->backend_->setInitialGuess(initialGuess); } template -bool iLQR::runIteration() +bool SingleShooting::runIteration() { prepareIteration(); @@ -44,19 +41,19 @@ bool iLQR::runIteratio } template -void iLQR::prepareIteration() +void SingleShooting::prepareIteration() { if (!this->backend_->isInitialized()) - throw std::runtime_error("iLQR is not initialized!"); + throw std::runtime_error("SingleShooting is not initialized!"); if (!this->backend_->isConfigured()) - throw std::runtime_error("iLQR is not configured!"); + throw std::runtime_error("SingleShooting is not configured!"); this->backend_->checkProblem(); } template -bool iLQR::finishIteration() +bool SingleShooting::finishIteration() { int K = this->backend_->getNumSteps(); @@ -80,47 +77,49 @@ bool iLQR::finishItera auto startEntire = start; // set box constraints and do LQ approximation - this->backend_->setBoxConstraintsForLQOCProblem(); + this->backend_->setInputBoxConstraintsForLQOCProblem(); + this->backend_->setStateBoxConstraintsForLQOCProblem(); this->backend_->computeLQApproximation(0, K - 1); auto end = std::chrono::steady_clock::now(); auto diff = end - start; if (debugPrint) - std::cout << "[iLQR]: Computing LQ approximation took " + std::cout << "[SingleShooting]: Computing LQ approximation took " << std::chrono::duration(diff).count() << " ms" << std::endl; end = std::chrono::steady_clock::now(); diff = end - startEntire; if (debugPrint) - std::cout << "[iLQR]: Forward pass took " << std::chrono::duration(diff).count() << " ms" - << std::endl; + std::cout << "[SingleShooting]: Forward pass took " << std::chrono::duration(diff).count() + << " ms" << std::endl; if (debugPrint) - std::cout << "[iLQR]: #2 Solve LQOC Problem" << std::endl; + std::cout << "[SingleShooting]: #2 Solve LQOC Problem" << std::endl; start = std::chrono::steady_clock::now(); this->backend_->solveFullLQProblem(); + this->backend_->extractSolution(); end = std::chrono::steady_clock::now(); diff = end - start; if (debugPrint) - std::cout << "[iLQR]: Solving LQOC problem took " << std::chrono::duration(diff).count() - << " ms" << std::endl; + std::cout << "[SingleShooting]: Solving LQOC problem took " + << std::chrono::duration(diff).count() << " ms" << std::endl; // update solutions and line-search if (debugPrint) - std::cout << "[iLQR]: #3 LineSearch" << std::endl; + std::cout << "[SingleShooting]: #3 LineSearch" << std::endl; start = std::chrono::steady_clock::now(); bool foundBetter = this->backend_->lineSearch(); end = std::chrono::steady_clock::now(); diff = end - start; if (debugPrint) - std::cout << "[iLQR]: Line search took " << std::chrono::duration(diff).count() << " ms" - << std::endl; + std::cout << "[SingleShooting]: Line search took " << std::chrono::duration(diff).count() + << " ms" << std::endl; diff = end - startEntire; if (debugPrint) - std::cout << "[iLQR]: finishIteration took " << std::chrono::duration(diff).count() << " ms" - << std::endl; + std::cout << "[SingleShooting]: finishIteration took " + << std::chrono::duration(diff).count() << " ms" << std::endl; this->backend_->printSummary(); @@ -134,13 +133,13 @@ bool iLQR::finishItera } template -void iLQR::prepareMPCIteration() +void SingleShooting::prepareMPCIteration() { prepareIteration(); } template -bool iLQR::finishMPCIteration() +bool SingleShooting::finishMPCIteration() { finishIteration(); return true; //! \todo : in MPC always returning true. Unclear how user wants to deal with varying costs, etc. diff --git a/ct_optcon/include/ct/optcon/nloc/algorithms/ilqr/iLQR.hpp b/ct_optcon/include/ct/optcon/nloc/algorithms/SingleShooting.hpp similarity index 70% rename from ct_optcon/include/ct/optcon/nloc/algorithms/ilqr/iLQR.hpp rename to ct_optcon/include/ct/optcon/nloc/algorithms/SingleShooting.hpp index c6ffe920b..9d4f4ea1c 100644 --- a/ct_optcon/include/ct/optcon/nloc/algorithms/ilqr/iLQR.hpp +++ b/ct_optcon/include/ct/optcon/nloc/algorithms/SingleShooting.hpp @@ -18,7 +18,7 @@ template -class iLQR : public NLOCAlgorithm +class SingleShooting final : public NLOCAlgorithm { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -36,10 +36,10 @@ class iLQR : public NLOCAlgorithm& backend_, const Settings_t& settings); + SingleShooting(std::shared_ptr& backend_, const Settings_t& settings); //! destructor - virtual ~iLQR(); + virtual ~SingleShooting() = default; //! configure the solver virtual void configure(const Settings_t& settings) override; @@ -50,33 +50,33 @@ class iLQR : public NLOCAlgorithmforwardZero(optVariables_->getOptimizationVars())(0); - else - return costEvaluator_->eval(); + return costEvaluator_->eval(); } @@ -80,13 +77,10 @@ class Nlp */ void evaluateCostGradient(const size_t n, MapVecXs& grad) { - if (!costCodegen_ && !costEvaluator_) + if (!costEvaluator_) throw std::runtime_error("Error in evaluateCostGradient. Costevaluator not initialized"); - if (costCodegen_) - grad = costCodegen_->jacobian(optVariables_->getOptimizationVars()); - else - costEvaluator_->evalGradient(n, grad); + costEvaluator_->evalGradient(n, grad); } /** @@ -97,13 +91,10 @@ class Nlp */ void evaluateConstraints(MapVecXs& values) { - if (!constraintsCodegen_ && !constraints_) + if (!constraints_) throw std::runtime_error("Error in evaluateConstraints. Constraints not initialized"); - if (constraintsCodegen_) - values = constraintsCodegen_->forwardZero(optVariables_->getOptimizationVars()); - else - constraints_->evalConstraints(values); + constraints_->evalConstraints(values); } /** @@ -114,13 +105,10 @@ class Nlp */ void evaluateConstraintJacobian(const int nele_jac, MapVecXs& jac) { - if (!constraintsCodegen_ && !constraints_) + if (!constraints_) throw std::runtime_error("Error in evaluateConstraintJacobian. Constraints not initialized"); - if (constraintsCodegen_) - jac = constraintsCodegen_->sparseJacobianValues(optVariables_->getOptimizationVars()); - else - constraints_->evalSparseJacobian(jac, nele_jac); + constraints_->evalSparseJacobian(jac, nele_jac); } /** @@ -144,17 +132,9 @@ class Nlp // evaluate Hessian values Eigen::VectorXd hessianCostValues, hessianConstraintsValues; - if (costCodegen_) - hessianCostValues = costCodegen_->sparseHessianValues(optVariables_->getOptimizationVars(), omega); - else - costEvaluator_->sparseHessianValues(optVariables_->getOptimizationVars(), omega, hessianCostValues); - + costEvaluator_->sparseHessianValues(optVariables_->getOptimizationVars(), omega, hessianCostValues); - if (constraintsCodegen_) - hessianConstraintsValues = - constraintsCodegen_->sparseHessianValues(optVariables_->getOptimizationVars(), lambda); - else - hessianConstraintsValues = constraints_->sparseHessianValues(optVariables_->getOptimizationVars(), lambda); + hessianConstraintsValues = constraints_->sparseHessianValues(optVariables_->getOptimizationVars(), lambda); // collect all Hessian values (from both constraints and cost) in one vector of triplets @@ -201,23 +181,13 @@ class Nlp */ void getSparsityPatternJacobian(const int nele_jac, MapVecXi& iRow, MapVecXi& jCol) const { - if (!constraintsCodegen_ && !constraints_) + if (!constraints_) throw std::runtime_error("Error in getSparsityPatternJacobian. Constraints not initialized"); iRow.setZero(); jCol.setZero(); - if (constraintsCodegen_) - { - Eigen::VectorXi iRow1; - Eigen::VectorXi jCol1; - constraintsCodegen_->getSparsityPatternJacobian(iRow1, jCol1); - - iRow = iRow1; - jCol = jCol1; - } - else - constraints_->getSparsityPattern(iRow, jCol, nele_jac); + constraints_->getSparsityPattern(iRow, jCol, nele_jac); } /** @@ -256,13 +226,10 @@ class Nlp */ size_t getNonZeroJacobianCount() const { - if (!constraintsCodegen_ && !constraints_) + if (!constraints_) throw std::runtime_error("Error in getNonZeroJacobianCount. Constraints not initialized"); - if (constraintsCodegen_) - return constraintsCodegen_->getNumNonZerosJacobian(); - else - return constraints_->getNonZerosJacobianCount(); + return constraints_->getNonZerosJacobianCount(); } /** @@ -288,16 +255,10 @@ class Nlp // evaluate sparsity patterns - if (constraintsCodegen_) - constraintsCodegen_->getSparsityPatternHessian(iRowHessianConstraints_, jColHessianConstraints_); - else - constraints_->getSparsityPatternHessian( - iRowHessianConstraints_, jColHessianConstraints_, optVariables_->size()); + constraints_->getSparsityPatternHessian( + iRowHessianConstraints_, jColHessianConstraints_, optVariables_->size()); - if (costCodegen_) - costCodegen_->getSparsityPatternHessian(iRowHessianCost_, jColHessianCost_); - else - costEvaluator_->getSparsityPatternHessian(iRowHessianCost_, jColHessianCost_); + costEvaluator_->getSparsityPatternHessian(iRowHessianCost_, jColHessianCost_); // collect all Hessian sparsity values (from both constraints and cost) in one vector of triplets @@ -535,12 +496,6 @@ class Nlp //! Ptr to constraint container, which contains the discretized constraints for the problem std::shared_ptr> constraints_; - //! Ptr to code-generated cost (optional) - std::shared_ptr> costCodegen_; - - //! Ptr to code-generated constraints (optional) - std::shared_ptr> constraintsCodegen_; - #if EIGEN_VERSION_AT_LEAST(3, 3, 0) Eigen::SparseMatrix Hessian_eval_; Eigen::SparseMatrix Hessian_sparsity_; // this is just a helper data structure @@ -552,7 +507,7 @@ class Nlp //! combined Hessian sparsity pattern gets stored here Eigen::VectorXi iRowHessian_, jColHessian_; }; -} +} // namespace tpl using Nlp = tpl::Nlp; diff --git a/ct_optcon/include/ct/optcon/nlp/solver/NlpSolverSettings.h b/ct_optcon/include/ct/optcon/nlp/solver/NlpSolverSettings.h index 633b3d9d4..68d49a4a5 100644 --- a/ct_optcon/include/ct/optcon/nlp/solver/NlpSolverSettings.h +++ b/ct_optcon/include/ct/optcon/nlp/solver/NlpSolverSettings.h @@ -145,7 +145,7 @@ class IpoptSettings point_perturbation_radius_(10), checkDerivativesForNaninf_("no"), derivativeTestPrintAll_("no"), - linearSystemScaling_("ma27"), + linearSystemScaling_("none"), linear_solver_("mumps"), jacobianApproximation_("finite-difference-values") { diff --git a/ct_optcon/include/ct/optcon/optcon-prespec.h b/ct_optcon/include/ct/optcon/optcon-prespec.h index 9b9e2891b..ae1f3eeca 100644 --- a/ct_optcon/include/ct/optcon/optcon-prespec.h +++ b/ct_optcon/include/ct/optcon/optcon-prespec.h @@ -28,8 +28,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #include "nloc/NLOCBackendBase.hpp" #include "nloc/NLOCBackendST.hpp" #include "nloc/NLOCBackendMP.hpp" -#include "nloc/algorithms/gnms/GNMS.hpp" -#include "nloc/algorithms/ilqr/iLQR.hpp" +#include "nloc/algorithms/MultipleShooting.hpp" +#include "nloc/algorithms/SingleShooting.hpp" #include "solver/OptConSolver.h" #include "solver/lqp/HPIPMInterface.hpp" diff --git a/ct_optcon/include/ct/optcon/optcon.h b/ct_optcon/include/ct/optcon/optcon.h index eabf2889c..3cbf68547 100644 --- a/ct_optcon/include/ct/optcon/optcon.h +++ b/ct_optcon/include/ct/optcon/optcon.h @@ -25,8 +25,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #include "nloc/NLOCBackendBase.hpp" #include "nloc/NLOCBackendST.hpp" #include "nloc/NLOCBackendMP.hpp" -#include "nloc/algorithms/gnms/GNMS.hpp" -#include "nloc/algorithms/ilqr/iLQR.hpp" +#include "nloc/algorithms/MultipleShooting.hpp" +#include "nloc/algorithms/SingleShooting.hpp" #include "solver/OptConSolver.h" #include "solver/lqp/HPIPMInterface.hpp" @@ -71,8 +71,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #include "nloc/NLOCBackendBase-impl.hpp" #include "nloc/NLOCBackendST-impl.hpp" #include "nloc/NLOCBackendMP-impl.hpp" -#include "nloc/algorithms/gnms/GNMS-impl.hpp" -#include "nloc/algorithms/ilqr/iLQR-impl.hpp" +#include "nloc/algorithms/MultipleShooting-impl.hpp" +#include "nloc/algorithms/SingleShooting-impl.hpp" #include "mpc/MPC-impl.h" #include "mpc/timehorizon/MpcTimeHorizon-impl.h" diff --git a/ct_optcon/include/ct/optcon/problem/LQOCProblem-impl.hpp b/ct_optcon/include/ct/optcon/problem/LQOCProblem-impl.hpp index f94311370..00266066b 100644 --- a/ct_optcon/include/ct/optcon/problem/LQOCProblem-impl.hpp +++ b/ct_optcon/include/ct/optcon/problem/LQOCProblem-impl.hpp @@ -11,8 +11,7 @@ namespace optcon { template LQOCProblem::LQOCProblem(int N) - : hasBoxConstraints_(false), // by default, we assume the problem ins unconstrained - hasGenConstraints_(false) + : hasInputBoxConstraints_(false), hasStateBoxConstraints_(false), hasGenConstraints_(false) { changeNumStages(N); } @@ -20,13 +19,19 @@ LQOCProblem::LQOCProblem(int N) template bool LQOCProblem::isConstrained() const { - return (isBoxConstrained() | isGeneralConstrained()); + return (isInputBoxConstrained() | isStateBoxConstrained() | isGeneralConstrained()); } template -bool LQOCProblem::isBoxConstrained() const +bool LQOCProblem::isInputBoxConstrained() const { - return hasBoxConstraints_; + return hasInputBoxConstraints_; +} + +template +bool LQOCProblem::isStateBoxConstrained() const +{ + return hasStateBoxConstraints_; } template @@ -50,9 +55,6 @@ void LQOCProblem::changeNumStages(int N) B_.resize(N); b_.resize(N + 1); - x_.resize(N + 1); - u_.resize(N); - P_.resize(N); q_.resize(N + 1); qv_.resize(N + 1); @@ -61,10 +63,15 @@ void LQOCProblem::changeNumStages(int N) rv_.resize(N); R_.resize(N); - ux_lb_.resize(N + 1); - ux_ub_.resize(N + 1); - ux_I_.resize(N + 1); - nb_.resize(N + 1); + x_lb_.resize(N + 1); + x_ub_.resize(N + 1); + x_I_.resize(N + 1); + u_lb_.resize(N); + u_ub_.resize(N); + u_I_.resize(N); + + nbx_.resize(N + 1); + nbu_.resize(N); ng_.resize(N + 1); d_lb_.resize(N + 1); @@ -80,8 +87,6 @@ void LQOCProblem::setZero(const int& nGenConstr) A_.setConstant(core::StateMatrix::Zero()); B_.setConstant(core::StateControlMatrix::Zero()); b_.setConstant(core::StateVector::Zero()); - x_.setConstant(core::StateVector::Zero()); - u_.setConstant(core::ControlVector::Zero()); P_.setConstant(core::FeedbackMatrix::Zero()); qv_.setConstant(core::StateVector::Zero()); Q_.setConstant(core::StateMatrix::Zero()); @@ -90,14 +95,16 @@ void LQOCProblem::setZero(const int& nGenConstr) q_.setConstant((SCALAR)0.0); // reset the number of box constraints + std::fill(nbx_.begin(), nbx_.end(), 0); + std::fill(nbu_.begin(), nbu_.end(), 0); // reset general constraints - std::fill(nb_.begin(), nb_.end(), 0); + assert(ng_.size() == d_lb_.size()); assert(d_lb_.size() == d_ub_.size()); assert(d_lb_.size() == C_.size()); assert(d_lb_.size() == D_.size()); std::fill(ng_.begin(), ng_.end(), nGenConstr); - for (size_t i = 0; i < d_lb_.size(); i++) + for (size_t i = 0; i < ng_.size(); i++) { d_lb_[i].resize(nGenConstr, 1); d_lb_[i].setZero(); @@ -109,74 +116,132 @@ void LQOCProblem::setZero(const int& nGenConstr) D_[i].setZero(); } - hasBoxConstraints_ = false; + hasInputBoxConstraints_ = false; + hasStateBoxConstraints_ = false; hasGenConstraints_ = false; } template -void LQOCProblem::setIntermediateBoxConstraint(const int index, +void LQOCProblem::setInputBoxConstraint(const int index, + const int nConstr, + const constr_vec_t& u_lb, + const constr_vec_t& u_ub, + const VectorXi& sp, + const ct::core::ControlVector& u_nom_abs) +{ + if ((u_lb.rows() != u_ub.rows()) | (u_lb.size() != nConstr) | (sp.rows() != nConstr) | + (sp(sp.rows() - 1) > (CONTROL_DIM - 1))) + { + std::cout << "n.o. constraints : " << nConstr << std::endl; + std::cout << "u_lb : " << u_lb.transpose() << std::endl; + std::cout << "u_ub : " << u_ub.transpose() << std::endl; + std::cout << "sparsity : " << sp.transpose() << std::endl; + throw(std::runtime_error("LQOCProblem setInputBoxConstraint: error in constraint config")); + } + + if (index >= K_) + throw(std::runtime_error("LQOCProblem cannot set an intermediate input Box constraint at time >= K_")); + + nbu_[index] = nConstr; + + // loop through box constraints and assign bounds in differential format + for (int i = 0; i < nConstr; i++) + { + u_I_[index](i) = sp(i); + u_lb_[index](i) = u_lb(i) - u_nom_abs(sp(i)); // substract the corresponding entry in nom-control + u_ub_[index](i) = u_ub(i) - u_nom_abs(sp(i)); // substract the corresponding entry in nom-control + } + hasInputBoxConstraints_ = true; +} + +template +void LQOCProblem::setInputBoxConstraints(const int nConstr, + const constr_vec_t& u_lb, + const constr_vec_t& u_ub, + const VectorXi& sp, + const ct::core::ControlVectorArray& u_nom_abs) +{ + for (int i = 0; i < K_; i++) + setInputBoxConstraint(i, nConstr, u_lb, u_ub, sp, u_nom_abs[i]); +} + + +template +void LQOCProblem::setIntermediateStateBoxConstraint(const int index, const int nConstr, - const constr_vec_t& ux_lb, - const constr_vec_t& ux_ub, - const VectorXi& sp) + const constr_vec_t& x_lb, + const constr_vec_t& x_ub, + const VectorXi& sp, + const ct::core::StateVector& x_nom_abs) { - if ((ux_lb.rows() != ux_ub.rows()) | (ux_lb.size() != nConstr) | (sp.rows() != nConstr) | - (sp(sp.rows() - 1) > (STATE_DIM + CONTROL_DIM - 1))) + if ((x_lb.rows() != x_ub.rows()) | (x_lb.size() != nConstr) | (sp.rows() != nConstr) | + (sp(sp.rows() - 1) > (STATE_DIM - 1))) { std::cout << "n.o. constraints : " << nConstr << std::endl; - std::cout << "ux_lb : " << ux_lb.transpose() << std::endl; - std::cout << "ux_ub : " << ux_ub.transpose() << std::endl; + std::cout << "x_lb : " << x_lb.transpose() << std::endl; + std::cout << "x_ub : " << x_ub.transpose() << std::endl; std::cout << "sparsity : " << sp.transpose() << std::endl; - throw(std::runtime_error("LQOCProblem setIntermediateBoxConstraint: error in constraint config")); + throw(std::runtime_error("LQOCProblem setIntermediateStateBoxConstraint: error in constraint config")); } if (index >= K_) - throw(std::runtime_error("LQOCProblem cannot set an intermediate Box constraint at time >= K_")); + throw(std::runtime_error("LQOCProblem cannot set an intermediate state Box constraint at time >= K_")); + + nbx_[index] = nConstr; - nb_[index] = nConstr; - ux_lb_[index].template topRows(nConstr) = ux_lb; - ux_ub_[index].template topRows(nConstr) = ux_ub; - ux_I_[index].template topRows(nConstr) = sp; + // loop through box constraints and assign bounds in differential format + for (int i = 0; i < nConstr; i++) + { + x_I_[index](i) = sp(i); + x_lb_[index](i) = x_lb(i) - x_nom_abs(sp(i)); // substract the corresponding entry in nom-state + x_ub_[index](i) = x_ub(i) - x_nom_abs(sp(i)); // substract the corresponding entry in nom-state + } - hasBoxConstraints_ = true; + hasStateBoxConstraints_ = true; } template -void LQOCProblem::setIntermediateBoxConstraints(const int nConstr, - const constr_vec_t& ux_lb, - const constr_vec_t& ux_ub, - const VectorXi& sp) +void LQOCProblem::setIntermediateStateBoxConstraints(const int nConstr, + const constr_vec_t& x_lb, + const constr_vec_t& x_ub, + const VectorXi& sp, + const ct::core::StateVectorArray& x_nom_abs) { for (int i = 0; i < K_; i++) - setIntermediateBoxConstraint(i, nConstr, ux_lb, ux_ub, sp); + setIntermediateStateBoxConstraint(i, nConstr, x_lb, x_ub, sp, x_nom_abs[i]); } template void LQOCProblem::setTerminalBoxConstraints(const int nConstr, - const constr_vec_t& ux_lb, - const constr_vec_t& ux_ub, - const VectorXi& sp) + const constr_vec_t& x_lb, + const constr_vec_t& x_ub, + const VectorXi& sp, + const ct::core::StateVector& x_nom_abs) { if (nConstr > 0) { - if ((ux_lb.rows() != ux_ub.rows()) | (ux_lb.size() != nConstr) | (sp.rows() != nConstr) | + if ((x_lb.rows() != x_ub.rows()) | (x_lb.size() != nConstr) | (sp.rows() != nConstr) | (sp(sp.rows() - 1) > (STATE_DIM - 1))) { std::cout << "n.o. constraints : " << nConstr << std::endl; - std::cout << "ux_lb : " << ux_lb.transpose() << std::endl; - std::cout << "ux_ub : " << ux_ub.transpose() << std::endl; + std::cout << "ux_lb : " << x_lb.transpose() << std::endl; + std::cout << "ux_ub : " << x_ub.transpose() << std::endl; std::cout << "sparsity : " << sp.transpose() << std::endl; throw(std::runtime_error("LQOCProblem setTerminalBoxConstraint: error in constraint config")); } - nb_[K_] = nConstr; - ux_lb_[K_].template topRows(nConstr) = ux_lb; - ux_ub_[K_].template topRows(nConstr) = ux_ub; - ux_I_[K_].template topRows(nConstr) = sp; + nbx_[K_] = nConstr; - hasBoxConstraints_ = true; + // loop through box constraints and assign bounds in differential format + for (int i = 0; i < nConstr; i++) + { + x_I_[K_](i) = sp(i); + x_lb_[K_](i) = x_lb(i) - x_nom_abs(sp(i)); // substract the corresponding entry in nom-state + x_ub_[K_](i) = x_ub(i) - x_nom_abs(sp(i)); // substract the corresponding entry in nom-state + } + hasStateBoxConstraints_ = true; } } @@ -197,17 +262,15 @@ void LQOCProblem::setGeneralConstraints(const co template void LQOCProblem::setFromTimeInvariantLinearQuadraticProblem( - ct::core::StateVector& x0, - ct::core::ControlVector& u0, ct::core::DiscreteLinearSystem& linearSystem, ct::optcon::CostFunctionQuadratic& costFunction, - ct::core::StateVector& offset, - double dt) + const ct::core::StateVector& offset, + const double dt) { setZero(); - x_ = core::StateVectorArray(K_ + 1, x0); - u_ = core::ControlVectorArray(K_, u0); + core::StateVector x0; x0.setZero(); // by definition + core::ControlVector u0; u0.setZero(); // by definition core::StateMatrix A; core::StateControlMatrix B; @@ -215,7 +278,7 @@ void LQOCProblem::setFromTimeInvariantLinearQuad A_ = core::StateMatrixArray(K_, A); B_ = core::StateControlMatrixArray(K_, B); - b_ = core::StateVectorArray(K_ + 1, offset + x0 - A * x0 - B * u0); + b_ = core::StateVectorArray(K_ + 1, offset); // feed current state and control to cost function costFunction.setCurrentStateAndControl(x0, u0, 0); @@ -226,16 +289,15 @@ void LQOCProblem::setFromTimeInvariantLinearQuad core::FeedbackArray(K_, costFunction.stateControlDerivativeIntermediate() * dt); R_ = core::ControlMatrixArray(K_, costFunction.controlSecondDerivativeIntermediate() * dt); - qv_ = core::StateVectorArray( - K_ + 1, costFunction.stateDerivativeIntermediate() * dt - Q_.front() * x0 - P_.front().transpose() * u0); - rv_ = core::ControlVectorArray( - K_, costFunction.controlDerivativeIntermediate() * dt - R_.front() * u0 - P_.front() * x0); + qv_ = core::StateVectorArray(K_ + 1, costFunction.stateDerivativeIntermediate() * dt); + rv_ = core::ControlVectorArray(K_, costFunction.controlDerivativeIntermediate() * dt); // final stage Q_[K_] = costFunction.stateSecondDerivativeTerminal(); - qv_[K_] = costFunction.stateDerivativeTerminal() - Q_[K_] * x0; + qv_[K_] = costFunction.stateDerivativeTerminal(); - hasBoxConstraints_ = false; + hasInputBoxConstraints_ = false; + hasStateBoxConstraints_ = false; hasGenConstraints_ = false; } diff --git a/ct_optcon/include/ct/optcon/problem/LQOCProblem.hpp b/ct_optcon/include/ct/optcon/problem/LQOCProblem.hpp index 725d456c9..c9978d793 100644 --- a/ct_optcon/include/ct/optcon/problem/LQOCProblem.hpp +++ b/ct_optcon/include/ct/optcon/problem/LQOCProblem.hpp @@ -11,47 +11,45 @@ namespace optcon { /*! * \brief Defines a Linear-Quadratic Optimal Control Problem, which is optionally constrained. * - * This class defines a Linear Quadratic Optimal Control (LQOC) Problem, consisting of + * This class defines a Linear Quadratic Optimal Control (LQOC) Problem in differential formulation, consisting of * - affine system dynamics - * - reference trajectories (arrays!) for state and control * - LQ approximation of the cost function * * The unconstrained LQ problem has the following form: * \f[ - * \min_{\mathbf{u}_n, \mathbf{x}_n} + * \min_{\delta \mathbf{u}_n, \delta \mathbf{x}_n} * \bigg \{ - * q_N + \mathbf{x}_N^\top \mathbf{q}_N +\frac{1}{2} \mathbf{x}_N^\top \mathbf{Q}_N \mathbf{x}_N - * +\sum_{n=0}^{N-1} q_n + \mathbf{x}_n^\top \mathbf{q}_n - * + \mathbf{u}_n^\top \mathbf{r}_n - * + \frac{1}{2} \mathbf{x}_n^\top\mathbf{Q}_n \mathbf{x}_n - * +\frac{1}{2} \mathbf{u}_n^\top \mathbf{R}_n \mathbf{u}_n - * + \mathbf{u}_n^\top \mathbf{P}_n \mathbf{x}_n + * q_N + \delta \mathbf{x}_N^\top \mathbf{q}_N +\frac{1}{2} \delta \mathbf{x}_N^\top \mathbf{Q}_N \delta \mathbf{x}_N + * +\sum_{n=0}^{N-1} q_n + \delta \mathbf{x}_n^\top \mathbf{q}_n + * + \delta \mathbf{u}_n^\top \mathbf{r}_n + * + \frac{1}{2} \delta \mathbf{x}_n^\top\mathbf{Q}_n \delta \mathbf{x}_n + * +\frac{1}{2} \delta \mathbf{u}_n^\top \mathbf{R}_n \delta \mathbf{u}_n + * + \delta \mathbf{u}_n^\top \mathbf{P}_n \delta \mathbf{x}_n * \bigg \} * \f] * subject to * \f[ - * \mathbf x_{n+1} = \mathbf A_n \mathbf x_n + \mathbf B_n \mathbf u_n +\mathbf b_n + * \mathbf \delta x_{n+1} = \mathbf A_n \delta \mathbf x_n + \mathbf B_n \delta \mathbf u_n +\mathbf b_n * \f] * * The constrained LQ problem additionally implements the box constraints - * \f$ \mathbf x_{lb} \leq \mathbf x_n \leq \mathbf x_{ub} \ \forall i=1,2,\ldots,N \f$ + * \f$ \mathbf x_{lb} \leq \mathbf \delta x_n \leq \mathbf x_{ub} \ \forall i=1,2,\ldots,N \f$ * and - * \f$ \mathbf u_{lb} \leq \mathbf u_n \leq \mathbf u_{ub} \ \forall i=0,1,\ldots,N-1\f$ + * \f$ \mathbf u_{lb} \leq \delta \mathbf u_n \leq \mathbf u_{ub} \ \forall i=0,1,\ldots,N-1\f$ * and the general inequality constraints * \f[ - * \mathbf d_{lb} \leq \mathbf C_n \mathbf x_n + \mathbf D_n \mathbf u_n \leq \mathbf d_{ub} \ \forall i=0,1,\ldots,N + * \mathbf d_{lb} \leq \mathbf C_n \delta \mathbf x_n + \mathbf D_n \delta \mathbf u_n \leq \mathbf d_{ub} \ \forall i=0,1,\ldots,N * \f] - * which are both always kept in absolute coordinates. + * which are both always kept in relative coordinates. * * \note The box constraint containers within this class are made fixed-size. Solvers can get the - * actual number of box constraints from a a dedicated container nb_ + * actual number of box constraints from a a dedicated container nbu_ and nbx_ * - * \note Note that until version v2.2 of the CT, we were using the differential notation + * \note In the differential notation we define * \f$ \delta \mathbf x_n = \mathbf x_n - \hat \mathbf x_n \f$ and \f$ \delta \mathbf u_n = \mathbf u_n - \hat \mathbf u_n \f$ + * where \hat \mathbf x_n and \hat \mathbf u_n are current nominal/reference trajectories, around which the LQP is formed. * - * with reference trajectories for state and control denoted as \f$ \hat \mathbf x_i, \ - * \hat \mathbf u_i \quad \forall i = 0, 1, \ldots \f$ - * however for consistency reasons, as of v2.3, the LQOC problem is formulated in absolute coordinates. + * \note this problem does not contain any state or control trajectory! The fundamental assumption is that \f$ \delta \mathbf x_0 = 0 \f$ * * \todo Refactor the initializing methods such that const-references can be handed over. */ @@ -69,12 +67,17 @@ class LQOCProblem using constr_state_jac_array_t = ct::core::DiscreteArray; using constr_control_jac_array_t = ct::core::DiscreteArray; - using box_constr_t = Eigen::Matrix; - using box_constr_array_t = ct::core::DiscreteArray; + using input_box_constr_vec_t = Eigen::Matrix; + using state_box_constr_vec_t = Eigen::Matrix; + using input_box_constr_array_t = ct::core::DiscreteArray; + using state_box_constr_array_t = ct::core::DiscreteArray; //! a vector indicating which box constraints are active and which not - using box_constr_sparsity_t = Eigen::Matrix; - using box_constr_sparsity_array_t = ct::core::DiscreteArray; + using state_box_constr_sparsity_t = Eigen::Matrix; + using input_box_constr_sparsity_t = Eigen::Matrix; + + using input_box_constr_sparsity_array_t = ct::core::DiscreteArray; + using state_box_constr_sparsity_array_t = ct::core::DiscreteArray; using VectorXi = Eigen::VectorXi; @@ -94,42 +97,77 @@ class LQOCProblem void setZero(const int& nGenConstr = 0); /*! - * \brief set intermediate box constraints at a specific index + * \brief set input box constraints at a specific index + * @param index the index + * @param nConstr the number of constraints + * @param u_lb control lower bound in absolute coordinates + * @param u_ub control upper bound in absolute coordinates + * @param sp the sparsity vector, with strictly increasing indices, e.g. [0 1 4 7] + */ + void setInputBoxConstraint(const int index, + const int nConstr, + const constr_vec_t& u_lb, + const constr_vec_t& u_ub, + const VectorXi& sp, + const ct::core::ControlVector& u_nom_abs); + + /*! + * \brief set uniform input box constraints, with the same constraint being applied at each intermediate stage + * @param nConstr the number of constraints + * @param u_lb control lower bound in absolute coordinates + * @param u_ub control upper bound in absolute coordinates + * @param sp the sparsity vector, with strictly increasing indices, e.g. [0 1 4 7] + * @param u_nom_abs current nominal control trajectory in absolute coordinates, required for coordinate transform + */ + void setInputBoxConstraints(const int nConstr, + const constr_vec_t& u_lb, + const constr_vec_t& u_ub, + const VectorXi& sp, + const ct::core::ControlVectorArray& u_nom_abs); + + /*! + * \brief set state box constraints at a specific index * @param index the index * @param nConstr the number of constraints - * @param ux_lb control lower bound in absolute coordinates, active bounds ordered as [u x] - * @param ux_ub control upper bound in absolute coordinates, active bounds ordered as [u x] + * @param x_lb state lower bound in absolute coordinates + * @param x_ub state upper bound in absolute coordinates * @param sp the sparsity vector, with strictly increasing indices, e.g. [0 1 4 7] + * @param x_nom_abs current nominal state vector in absolute coordinates, required for coordinate transform */ - void setIntermediateBoxConstraint(const int index, + void setIntermediateStateBoxConstraint(const int index, const int nConstr, - const constr_vec_t& ux_lb, - const constr_vec_t& ux_ub, - const VectorXi& sp); + const constr_vec_t& x_lb, + const constr_vec_t& x_ub, + const VectorXi& sp, + const ct::core::StateVector& x_nom_abs); /*! - * \brief set uniform box constraints, with the same constraint being applied at each intermediate stage + * \brief set uniform state box constraints, with the same constraint being applied at each intermediate stage * @param nConstr the number of constraints - * @param ux_lb control lower bound in absolute coordinates, active bounds ordered as [u x] - * @param ux_ub control upper bound in absolute coordinates, active bounds ordered as [u x] + * @param x_lb control lower bound in absolute coordinates + * @param x_ub control upper bound in absolute coordinates * @param sp the sparsity vector, with strictly increasing indices, e.g. [0 1 4 7] + * @param x_nom_abs current nominal state trajectory in absolute coordinates, required for coordinate transform */ - void setIntermediateBoxConstraints(const int nConstr, - const constr_vec_t& ux_lb, - const constr_vec_t& ux_ub, - const VectorXi& sp); + void setIntermediateStateBoxConstraints(const int nConstr, + const constr_vec_t& x_lb, + const constr_vec_t& x_ub, + const VectorXi& sp, + const ct::core::StateVectorArray& x_nom_abs); /*! * \brief set box constraints for terminal stage * @param nConstr the number of constraints - * @param ux_lb control lower bound in absolute coordinates, active bounds ordered as [u x] - * @param ux_ub control upper bound in absolute coordinates, active bounds ordered as [u x] + * @param x_lb state lower bound in absolute coordinates + * @param x_ub state upper bound in absolute coordinates * @param sp the sparsity vector, with strictly increasing indices, e.g. [0 1 4 7] + * @param x_nom_abs current nominal terminal state vector in absolute coordinates, required for coordinate transform */ void setTerminalBoxConstraints(const int nConstr, - const constr_vec_t& ux_lb, - const constr_vec_t& ux_ub, - const VectorXi& sp); + const constr_vec_t& x_lb, + const constr_vec_t& x_ub, + const VectorXi& sp, + const ct::core::StateVector& x_nom_abs); /*! * \brief set general (in)equaltiy constraints, with the same constraint applied at each stage @@ -146,24 +184,22 @@ class LQOCProblem /*! * \brief a convenience method which constructs an unconstrained LQOC Problem from an LTI system and continuous-time quadratic cost * The discretization of the cost functions happens within this function. It employs an Euler-Discretization - * @param x0 the initial state - * @param u0 the current (and desired control) * @param linearSystem the discrete-time LTI system * @param costFunction the continuous-time cost function * @param stateOffset the offset for the affine system dynamics demanded by the LQOC Solver * @param dt the sampling time, required for discretization */ - void setFromTimeInvariantLinearQuadraticProblem(ct::core::StateVector& x0, - ct::core::ControlVector& u0, + void setFromTimeInvariantLinearQuadraticProblem( ct::core::DiscreteLinearSystem& linearSystem, ct::optcon::CostFunctionQuadratic& costFunction, - ct::core::StateVector& stateOffset, - double dt); + const ct::core::StateVector& stateOffset, + const double dt); //! return a flag indicating whether this LQOC Problem is constrained or not bool isConstrained() const; - bool isBoxConstrained() const; + bool isInputBoxConstrained() const; + bool isStateBoxConstrained() const; bool isGeneralConstrained() const; //! affine, time-varying system dynamics in discrete time @@ -171,12 +207,6 @@ class LQOCProblem ct::core::StateControlMatrixArray B_; ct::core::StateVectorArray b_; - //! reference state trajectory - ct::core::StateVectorArray x_; - - //! reference control trajectory - ct::core::ControlVectorArray u_; - //! constant term of in the LQ approximation of the cost function ct::core::ScalarArray q_; @@ -191,19 +221,25 @@ class LQOCProblem //! LQ approximation of the cross terms of the cost function ct::core::FeedbackArray P_; - //! lower bound of box constraints in order [u_lb; x_lb]. Stacked for memory efficiency. - box_constr_array_t ux_lb_; - //! upper bound of box constraints in order [u_ub; x_ub]. Stacked for memory efficiency. - box_constr_array_t ux_ub_; + //! bounds of box constraints for input and state + input_box_constr_array_t u_lb_; + input_box_constr_array_t u_ub_; + state_box_constr_array_t x_lb_; + state_box_constr_array_t x_ub_; + /*! * \brief container for the box constraint sparsity pattern * An example for how an element of this array might look like: [0 1 4 7] - * This would mean that box constraints act on elements 0, 1, 4 and 7 of the - * combined vector of decision variables [u; x] + * This would mean that box constraints act on elements 0, 1, 4 and 7 of the state or input vector */ - box_constr_sparsity_array_t ux_I_; - //! the number of box constraints at every stage. - std::vector nb_; + input_box_constr_sparsity_array_t u_I_; + state_box_constr_sparsity_array_t x_I_; + + //! the number of input box constraints at every stage. + std::vector nbu_; + + //! the number of state box constraints at every stage. + std::vector nbx_; //! general constraint lower bound constr_vec_array_t d_lb_; @@ -216,7 +252,8 @@ class LQOCProblem std::vector ng_; //! bool indicating if the optimization problem is box-constrained - bool hasBoxConstraints_; + bool hasInputBoxConstraints_; + bool hasStateBoxConstraints_; //! bool indicating if the optimization problem hs general inequality constraints bool hasGenConstraints_; diff --git a/ct_optcon/include/ct/optcon/problem/OptConProblemBase-impl.h b/ct_optcon/include/ct/optcon/problem/OptConProblemBase-impl.h index 1adc11f46..ebbc02680 100644 --- a/ct_optcon/include/ct/optcon/problem/OptConProblemBase-impl.h +++ b/ct_optcon/include/ct/optcon/problem/OptConProblemBase-impl.h @@ -34,7 +34,8 @@ OptConProblemBase::OptConProblemBase( DynamicsPtr_t nonlinDynamics, CostFunctionPtr_t costFunction, - ConstraintPtr_t boxConstraints, + ConstraintPtr_t inputBoxConstraints, + ConstraintPtr_t stateBoxConstraints, ConstraintPtr_t generalConstraints, LinearPtr_t linearSystem) : OptConProblemBase(nonlinDynamics, costFunction, linearSystem) // delegating constructor { - boxConstraints_ = boxConstraints; + inputBoxConstraints_ = inputBoxConstraints; + stateBoxConstraints_ = stateBoxConstraints; generalConstraints_ = generalConstraints; } @@ -93,12 +96,14 @@ OptConProblemBase -void OptConProblemBase::setBoxConstraints( +void OptConProblemBase::setInputBoxConstraints( const ConstraintPtr_t constraint) { - boxConstraints_ = constraint; - if (!boxConstraints_->isInitialized()) - boxConstraints_->initialize(); + inputBoxConstraints_ = constraint; + if (!inputBoxConstraints_->isInitialized()) + inputBoxConstraints_->initialize(); +} + +template +void OptConProblemBase::setStateBoxConstraints( + const ConstraintPtr_t constraint) +{ + stateBoxConstraints_ = constraint; + if (!stateBoxConstraints_->isInitialized()) + stateBoxConstraints_->initialize(); } template const typename OptConProblemBase:: ConstraintPtr_t - OptConProblemBase::getBoxConstraints() + OptConProblemBase::getInputBoxConstraints() + const +{ + return inputBoxConstraints_; +} + +template +const typename OptConProblemBase:: + ConstraintPtr_t + OptConProblemBase::getStateBoxConstraints() const { - return boxConstraints_; + return stateBoxConstraints_; } template lineSearchTypeToString = {{NONE, "NONE (take full-step updates with alpha=1.0)"}, + {SIMPLE, "Simple Backtracking with cost/merit"}, {ARMIJO, "ARMIJO-style Backtracking for single-shooting"}, + {GOLDSTEIN, "GOLDSTEIN backtracking using Riccati matrices"}}; + + std::map stringToLineSearchType = { + {"NONE", NONE}, {"SIMPLE", SIMPLE}, {"ARMIJO", ARMIJO}, {"GOLDSTEIN", GOLDSTEIN}}; + + //! default constructor for the NLOptCon line-search settings LineSearchSettings() - : active(true), + : type(NONE), adaptive(false), maxIterations(10), alpha_0(1.0), alpha_max(1.0), n_alpha(0.5), + armijo_parameter(0.01), debugPrint(false) { } //! check if the currently set line-search parameters are meaningful bool parametersOk() const { return (alpha_0 > 0.0) && (n_alpha > 0.0) && (n_alpha < 1.0) && (alpha_max > 0.0); } - bool active; /*!< Flag whether or not to perform line search */ + TYPE type; /*!< type of line search */ bool adaptive; /*!< Flag whether alpha_0 gets updated based on previous iteration */ size_t maxIterations; /*!< Maximum number of iterations during line search */ double alpha_0; /*!< Initial step size for line search. Use 1 for step size as suggested by NLOptCon */ double alpha_max; /*!< Maximum step size for line search. This is the limit when adapting alpha_0. */ double - n_alpha; /*!< Factor by which the line search step size alpha gets multiplied with after each iteration. Usually 0.5 is a good value. */ - bool debugPrint; /*!< Print out debug information during line-search*/ + n_alpha; /*!< Factor by which the step size alpha gets scaled after each iteration. Usually 0.5 is a good value. */ + double armijo_parameter; /*!< "Control Parameter" in Armijo line search condition. */ + bool debugPrint; /*!< Print out debug information during line-search*/ //! print the current line search settings to console @@ -50,12 +71,13 @@ struct LineSearchSettings { std::cout << "Line Search Settings: " << std::endl; std::cout << "=====================" << std::endl; - std::cout << "active:\t" << active << std::endl; + std::cout << "type:\t" << lineSearchTypeToString.at(type) << std::endl; std::cout << "adaptive:\t" << adaptive << std::endl; std::cout << "maxIter:\t" << maxIterations << std::endl; std::cout << "alpha_0:\t" << alpha_0 << std::endl; std::cout << "alpha_max:\t" << alpha_max << std::endl; std::cout << "n_alpha:\t" << n_alpha << std::endl; + std::cout << "armijo_parameter:\t" << armijo_parameter << std::endl; std::cout << "debugPrint:\t" << debugPrint << std::endl; std::cout << " =======" << std::endl; std::cout << std::endl; @@ -70,7 +92,24 @@ struct LineSearchSettings boost::property_tree::ptree pt; boost::property_tree::read_info(filename, pt); - active = pt.get(ns + ".active"); + std::string ls_type = pt.get(ns + ".type"); + if (stringToLineSearchType.find(ls_type) != stringToLineSearchType.end()) + { + type = stringToLineSearchType[ls_type]; + } + else + { + std::cout << "Invalid line search type specified in config, should be one of the following:" << std::endl; + + for (auto it = stringToLineSearchType.begin(); it != stringToLineSearchType.end(); it++) + { + std::cout << it->first << std::endl; + } + + exit(-1); + } + + maxIterations = pt.get(ns + ".maxIterations"); alpha_0 = pt.get(ns + ".alpha_0"); n_alpha = pt.get(ns + ".n_alpha"); @@ -78,9 +117,22 @@ struct LineSearchSettings alpha_max = alpha_0; adaptive = false; + try + { + armijo_parameter = pt.get(ns + ".armijo_parameter"); + } catch (...) + { + } + try { adaptive = pt.get(ns + ".adaptive"); + } catch (...) + { + } + + try + { alpha_max = pt.get(ns + ".alpha_max"); } catch (...) { @@ -102,9 +154,10 @@ struct LineSearchSettings struct LQOCSolverSettings { public: - LQOCSolverSettings() : num_lqoc_iterations(5), lqoc_debug_print(false) {} - int num_lqoc_iterations; //! number of allowed sub-iterations of LQOC solver per NLOC main iteration + LQOCSolverSettings() : lqoc_debug_print(false), num_lqoc_iterations(10) {} + bool lqoc_debug_print; + int num_lqoc_iterations; //! number of allowed sub-iterations of LQOC solver per NLOC main iteration void print() const { @@ -145,13 +198,16 @@ struct LQOCSolverSettings class NLOptConSettings { public: - typedef typename core::SensitivityApproximationSettings::APPROXIMATION APPROXIMATION; - - //! the nonlinear optimal control problem solving algorithm + //! algorithm types for solving the NLOC problem enum NLOCP_ALGORITHM { - GNMS = 0, - ILQR, + GNMS = 0, //! Gauss-Newton Multiple Shooting (shooting interval = control interval) + ILQR, //! Classical iLQR (1 shooting interval equal to problem horizon) + MS_ILQR, //! multiple-shooting iLQR + SS_OL, //! Classical (open-loop) Single Shooting + SS_CL, //! Closed-loop single shooting + GNMS_M_OL, //! GNMS(M) with open-loop shooting + GNMS_M_CL, //! GNMS(M) with closed-loop shooting NUM_TYPES }; @@ -162,6 +218,7 @@ class NLOptConSettings HPIPM_SOLVER = 1 }; + using APPROXIMATION = typename core::SensitivityApproximationSettings::APPROXIMATION; //! NLOptCon Settings default constructor /*! @@ -174,7 +231,6 @@ class NLOptConSettings nlocp_algorithm(GNMS), lqocp_solver(GNRICCATI_SOLVER), loggingPrefix("alg"), - closedLoopShooting(false), //! by default, we do open-loop shooting epsilon(1e-5), dt(0.001), K_sim(1), //! by default, there is only one sub-integration step @@ -202,7 +258,6 @@ class NLOptConSettings NLOCP_ALGORITHM nlocp_algorithm; //! which nonlinear optimal control algorithm is to be used LQOCP_SOLVER lqocp_solver; //! the solver for the linear-quadratic optimal control problem std::string loggingPrefix; //! the prefix to be stored before the matfile name for logging - bool closedLoopShooting; //! use feedback gains during forward integration (true) or not (false) double epsilon; //! Eigenvalue correction factor for Hessian regularization double dt; //! sampling time for the control input (seconds) int K_sim; //! number of sub-integration-steps @@ -211,12 +266,12 @@ class NLOptConSettings double maxDefectSum; //! maximum sum of squared defects (assume covergence if lower than this number) double meritFunctionRho; //! trade off between internal (defect)constraint violation and cost double meritFunctionRhoConstraints; //! trade off between external (general and path) constraint violation and cost - int max_iterations; //! the maximum admissible number of NLOptCon main iterations \warning make sure to select this number high enough allow for convergence - bool fixedHessianCorrection; //! perform Hessian regularization by incrementing the eigenvalues by epsilon. - bool recordSmallestEigenvalue; //! save the smallest eigenvalue of the Hessian - int nThreads; //! number of threads, for MP version + int max_iterations; //! the maximum admissible number of NLOptCon main iterations \warning make sure to select this number high enough allow for convergence + bool fixedHessianCorrection; //! perform Hessian regularization by incrementing the eigenvalues by epsilon. + bool recordSmallestEigenvalue; //! save the smallest eigenvalue of the Hessian + int nThreads; //! number of threads, for MP version size_t - nThreadsEigen; //! number of threads for eigen parallelization (applies both to MP and ST) Note. in order to activate Eigen parallelization, compile with '-fopenmp' + nThreadsEigen; //! number of threads for eigen parallelization (applies both to MP and ST) Note. in order to activate Eigen parallelization, compile with '-fopenmp' LineSearchSettings lineSearchSettings; //! the line search settings LQOCSolverSettings lqoc_solver_settings; bool debugPrint; @@ -241,7 +296,15 @@ class NLOptConSettings return std::max(1, (int)std::lround(timeHorizon / dt)); } + //! compute the simulation timestep double getSimulationTimestep() const { return (dt / (double)K_sim); } + + //! return if this is a closed-loop shooting algorithm (or not) + bool closedLoopShooting() const { return nlocAlgorithmToClosedLoopShooting.at(nlocp_algorithm); } + + //! return if this is a single-shooting algorithm (or not) + bool isSingleShooting() const { return nlocAlgorithmToSingleShooting.at(nlocp_algorithm); } + //! print the current NLOptCon settings to console void print() const { @@ -250,9 +313,8 @@ class NLOptConSettings std::cout << "integrator: " << integratorToString.at(integrator) << std::endl; std::cout << "discretization: " << discretizationToString.at(discretization) << std::endl; std::cout << "time varying discretization: " << timeVaryingDiscretization << std::endl; - std::cout << "nonlinear OCP algorithm: " << nlocp_algorithmToString.at(nlocp_algorithm) << std::endl; - std::cout << "linear-quadratic OCP solver: " << locp_solverToString.at(lqocp_solver) << std::endl; - std::cout << "closed loop shooting:\t" << closedLoopShooting << std::endl; + std::cout << "nonlinear OCP algorithm: " << nlocAlgorithmToString.at(nlocp_algorithm) << std::endl; + std::cout << "linear-quadratic OCP solver: " << lqocSolverToString.at(lqocp_solver) << std::endl; std::cout << "dt:\t" << dt << std::endl; std::cout << "K_sim:\t" << K_sim << std::endl; std::cout << "K_shot:\t" << K_shot << std::endl; @@ -394,12 +456,6 @@ class NLOptConSettings { } try - { - closedLoopShooting = pt.get(ns + ".closedLoopShooting"); - } catch (...) - { - } - try { debugPrint = pt.get(ns + ".debugPrint"); } catch (...) @@ -511,16 +567,16 @@ class NLOptConSettings } std::string nlocp_algorithmStr = pt.get(ns + ".nlocp_algorithm"); - if (stringTonlocp_algorithm.find(nlocp_algorithmStr) != stringTonlocp_algorithm.end()) + if (stringToNlocAlgorithm.find(nlocp_algorithmStr) != stringToNlocAlgorithm.end()) { - nlocp_algorithm = stringTonlocp_algorithm[nlocp_algorithmStr]; + nlocp_algorithm = stringToNlocAlgorithm[nlocp_algorithmStr]; } else { std::cout << "Invalid nlocp_algorithm specified in config, should be one of the following:" << std::endl; - for (auto it = stringTonlocp_algorithm.begin(); it != stringTonlocp_algorithm.end(); it++) + for (auto it = stringToNlocAlgorithm.begin(); it != stringToNlocAlgorithm.end(); it++) { std::cout << it->first << std::endl; } @@ -530,15 +586,15 @@ class NLOptConSettings std::string locp_solverStr = pt.get(ns + ".locp_solver"); - if (stringTolocp_solver.find(locp_solverStr) != stringTolocp_solver.end()) + if (stringToLqocSolver.find(locp_solverStr) != stringToLqocSolver.end()) { - lqocp_solver = stringTolocp_solver[locp_solverStr]; + lqocp_solver = stringToLqocSolver[locp_solverStr]; } else { std::cout << "Invalid locp_solver specified in config, should be one of the following:" << std::endl; - for (auto it = stringTolocp_solver.begin(); it != stringTolocp_solver.end(); it++) + for (auto it = stringToLqocSolver.begin(); it != stringToLqocSolver.end(); it++) { std::cout << it->first << std::endl; } @@ -605,16 +661,26 @@ class NLOptConSettings //! mappings for algorithm types - std::map nlocp_algorithmToString = {{GNMS, "GNMS"}, {ILQR, "ILQR"}}; + std::map nlocAlgorithmToString = {{GNMS, "GNMS (Gauss-Newton Multiple Shooting)"}, + {ILQR, "ILQR (iterative linear-quadratic optimal control)"}, {MS_ILQR, "MS_ILQR (multiple-shooting iLQR)"}, + {SS_OL, "SS_OL (open-loop Single Shooting)"}, {SS_CL, "SS_CL (closed-loop Single Shooting)"}, + {GNMS_M_OL, "GNMS_M_OL (GNMS(M) with open-loop shooting)"}, + {GNMS_M_CL, "GNMS_M_CL (GNMS(M) with closed-loop shooting)"}}; + + std::map stringToNlocAlgorithm = {{"GNMS", GNMS}, {"ILQR", ILQR}, + {"MS_ILQR", MS_ILQR}, {"SS_OL", SS_OL}, {"SS_CL", SS_CL}, {"GNMS_M_OL", GNMS_M_OL}, {"GNMS_M_CL", GNMS_M_CL}}; - std::map stringTonlocp_algorithm = {{"GNMS", GNMS}, {"ILQR", ILQR}}; + std::map nlocAlgorithmToClosedLoopShooting = {{GNMS, false}, {ILQR, true}, {MS_ILQR, true}, + {SS_OL, false}, {SS_CL, true}, {GNMS_M_OL, false}, {GNMS_M_CL, true}}; + std::map nlocAlgorithmToSingleShooting = {{GNMS, false}, {ILQR, true}, {MS_ILQR, false}, + {SS_OL, true}, {SS_CL, true}, {GNMS_M_OL, false}, {GNMS_M_CL, false}}; //! mappings for linear-quadratic solver types - std::map locp_solverToString = { + std::map lqocSolverToString = { {GNRICCATI_SOLVER, "GNRICCATI_SOLVER"}, {HPIPM_SOLVER, "HPIPM_SOLVER"}}; - std::map stringTolocp_solver = { + std::map stringToLqocSolver = { {"GNRICCATI_SOLVER", GNRICCATI_SOLVER}, {"HPIPM_SOLVER", HPIPM_SOLVER}}; }; } // namespace optcon diff --git a/ct_optcon/include/ct/optcon/solver/NLOptConSolver-impl.hpp b/ct_optcon/include/ct/optcon/solver/NLOptConSolver-impl.hpp index 6ee27fd1b..383e3311b 100644 --- a/ct_optcon/include/ct/optcon/solver/NLOptConSolver-impl.hpp +++ b/ct_optcon/include/ct/optcon/solver/NLOptConSolver-impl.hpp @@ -27,28 +27,18 @@ NLOptConSolver::NLOptC { } - -template -NLOptConSolver::~NLOptConSolver() -{ -} - - template void NLOptConSolver::setAlgorithm(const Settings_t& settings) { - switch (settings.nlocp_algorithm) + if (settings.isSingleShooting()) { - case NLOptConSettings::NLOCP_ALGORITHM::GNMS: - nlocAlgorithm_ = std::shared_ptr>( - new GNMS(nlocBackend_, settings)); - break; - case NLOptConSettings::NLOCP_ALGORITHM::ILQR: - nlocAlgorithm_ = std::shared_ptr>( - new iLQR(nlocBackend_, settings)); - break; - default: - throw std::runtime_error("This algorithm is not implemented in NLOptConSolver.hpp"); + nlocAlgorithm_ = std::shared_ptr>( + new SingleShooting(nlocBackend_, settings)); + } + else + { + nlocAlgorithm_ = std::shared_ptr>( + new MultipleShooting(nlocBackend_, settings)); } } @@ -307,18 +297,35 @@ NLOptConSolver::getCos template std::vector::OptConProblem_t:: ConstraintPtr_t>& -NLOptConSolver::getBoxConstraintsInstances() +NLOptConSolver::getInputBoxConstraintsInstances() +{ + return nlocBackend_->getInputBoxConstraintsInstances(); +} + + +template +const std::vector::OptConProblem_t:: + ConstraintPtr_t>& +NLOptConSolver::getInputBoxConstraintsInstances() const +{ + return nlocBackend_->getInputBoxConstraintsInstances(); +} + +template +std::vector::OptConProblem_t:: + ConstraintPtr_t>& +NLOptConSolver::getStateBoxConstraintsInstances() { - return nlocBackend_->getBoxConstraintsInstances(); + return nlocBackend_->getStateBoxConstraintsInstances(); } template const std::vector::OptConProblem_t:: ConstraintPtr_t>& -NLOptConSolver::getBoxConstraintsInstances() const +NLOptConSolver::getStateBoxConstraintsInstances() const { - return nlocBackend_->getBoxConstraintsInstances(); + return nlocBackend_->getStateBoxConstraintsInstances(); } diff --git a/ct_optcon/include/ct/optcon/solver/NLOptConSolver.hpp b/ct_optcon/include/ct/optcon/solver/NLOptConSolver.hpp index 7f7d873fe..aa5578e2f 100644 --- a/ct_optcon/include/ct/optcon/solver/NLOptConSolver.hpp +++ b/ct_optcon/include/ct/optcon/solver/NLOptConSolver.hpp @@ -10,8 +10,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #include #include -#include -#include +#include +#include namespace ct { namespace optcon { @@ -26,13 +26,14 @@ template -class NLOptConSolver : public OptConSolver, - typename NLOCAlgorithm::Policy_t, - NLOptConSettings, - STATE_DIM, - CONTROL_DIM, - SCALAR, - CONTINUOUS> +class NLOptConSolver final + : public OptConSolver, + typename NLOCAlgorithm::Policy_t, + NLOptConSettings, + STATE_DIM, + CONTROL_DIM, + SCALAR, + CONTINUOUS> { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -72,7 +73,7 @@ class NLOptConSolver : public OptConSolver& getCostFunctionInstances() const override; //! get reference to the box constraints - std::vector& getBoxConstraintsInstances() override; + std::vector& getInputBoxConstraintsInstances() override; //! get constant reference to the boxconstraints - const std::vector& getBoxConstraintsInstances() const override; + const std::vector& getInputBoxConstraintsInstances() const override; + + //! get reference to the box constraints + std::vector& getStateBoxConstraintsInstances() override; + + //! get constant reference to the boxconstraints + const std::vector& getStateBoxConstraintsInstances() const override; //! get reference to the general constraints std::vector& getGeneralConstraintsInstances() override; diff --git a/ct_optcon/include/ct/optcon/solver/OptConSolver.h b/ct_optcon/include/ct/optcon/solver/OptConSolver.h index 07cdf29e4..9db9252f3 100644 --- a/ct_optcon/include/ct/optcon/solver/OptConSolver.h +++ b/ct_optcon/include/ct/optcon/solver/OptConSolver.h @@ -80,8 +80,10 @@ class OptConSolver changeNonlinearSystem(optConProblem.getNonlinearSystem()); changeLinearSystem(optConProblem.getLinearSystem()); - if (optConProblem.getBoxConstraints()) - changeBoxConstraints(optConProblem.getBoxConstraints()); + if (optConProblem.getInputBoxConstraints()) + changeInputBoxConstraints(optConProblem.getInputBoxConstraints()); + if (optConProblem.getStateBoxConstraints()) + changeStateBoxConstraints(optConProblem.getStateBoxConstraints()); if (optConProblem.getGeneralConstraints()) changeGeneralConstraints(optConProblem.getGeneralConstraints()); } @@ -201,9 +203,14 @@ class OptConSolver * * @param[in] con The new box constraints */ - virtual void changeBoxConstraints(const typename OptConProblem_t::ConstraintPtr_t con) + virtual void changeInputBoxConstraints(const typename OptConProblem_t::ConstraintPtr_t con) { - throw std::runtime_error("The current solver does not support constraints!"); + throw std::runtime_error("The current solver does not support input box constraints!"); + } + + virtual void changeStateBoxConstraints(const typename OptConProblem_t::ConstraintPtr_t con) + { + throw std::runtime_error("The current solver does not support state box constraints!"); } /** @@ -270,9 +277,26 @@ class OptConSolver * * @return The state box constraint instances */ - virtual std::vector& getBoxConstraintsInstances() = 0; + virtual std::vector& getInputBoxConstraintsInstances() + { + throw std::runtime_error("getInputBoxConstraintsInstances not supported."); + } + + virtual const std::vector& getInputBoxConstraintsInstances() const + { + throw std::runtime_error("getInputBoxConstraintsInstances not supported."); + } + + virtual std::vector& getStateBoxConstraintsInstances() + { + throw std::runtime_error("getStateBoxConstraintsInstances not supported."); + } + + virtual const std::vector& getStateBoxConstraintsInstances() const + { + throw std::runtime_error("getStateBoxConstraintsInstances not supported."); + } - virtual const std::vector& getBoxConstraintsInstances() const = 0; /** * @brief Direct accessor to the general constraints @@ -284,9 +308,15 @@ class OptConSolver * * @return The general constraints instances. */ - virtual std::vector& getGeneralConstraintsInstances() = 0; + virtual std::vector& getGeneralConstraintsInstances() + { + throw std::runtime_error("getGeneralConstraintsInstances not supported."); + } - virtual const std::vector& getGeneralConstraintsInstances() const = 0; + virtual const std::vector& getGeneralConstraintsInstances() const + { + throw std::runtime_error("getGeneralConstraintsInstances not supported."); + } /** @@ -317,5 +347,5 @@ class OptConSolver throw std::runtime_error("Generate Code not implemented for this solver"); } }; -} -} +} // namespace optcon +} // namespace ct diff --git a/ct_optcon/include/ct/optcon/solver/lqp/GNRiccatiSolver-impl.hpp b/ct_optcon/include/ct/optcon/solver/lqp/GNRiccatiSolver-impl.hpp index b162e5891..74021f1ef 100644 --- a/ct_optcon/include/ct/optcon/solver/lqp/GNRiccatiSolver-impl.hpp +++ b/ct_optcon/include/ct/optcon/solver/lqp/GNRiccatiSolver-impl.hpp @@ -24,20 +24,11 @@ GNRiccatiSolver::GNRiccatiSolver(int N) changeNumberOfStages(N); } - -template -GNRiccatiSolver::~GNRiccatiSolver() -{ -} - - template void GNRiccatiSolver::solve() { for (int i = this->lqocProblem_->getNumberOfStages() - 1; i >= 0; i--) solveSingleStage(i); - - extractLQSolution(); } @@ -62,22 +53,31 @@ void GNRiccatiSolver::configure(const NLOptConSe } template -void GNRiccatiSolver::extractLQSolution() +void GNRiccatiSolver::computeStatesAndControls() { LQOCProblem_t& p = *this->lqocProblem_; - this->x_sol_[0] = p.x_[0]; + this->x_sol_[0].setZero(); // should always be zero (fixed init state) for (int k = 0; k < this->lqocProblem_->getNumberOfStages(); k++) { - //! control update rule - this->u_sol_[k] = lv_[k] + this->L_[k] * this->x_sol_[k]; + //! control update rule in diff coordinates + this->u_sol_[k] = this->lv_[k] + this->L_[k] * this->x_sol_[k]; - //! state update rule - this->x_sol_[k + 1] = p.A_[k] * this->x_sol_[k] + p.B_[k] * this->u_sol_[k] + p.b_[k]; + //! state update rule in diff coordinates + this->x_sol_[k + 1] = p.A_[k] * this->x_sol_[k] + p.B_[k] * (this->u_sol_[k]) + p.b_[k]; } } +template +void GNRiccatiSolver::computeFeedbackMatrices() +{ /*no action required, already computed in backward pass */ +} + +template +void GNRiccatiSolver::compute_lv() +{ /*no action required, already computed in backward pass*/ +} template SCALAR GNRiccatiSolver::getSmallestEigenvalue() @@ -85,7 +85,6 @@ SCALAR GNRiccatiSolver::getSmallestEigenvalue() return smallestEigenvalue_; } - template void GNRiccatiSolver::setProblemImpl(std::shared_ptr lqocProblem) { @@ -116,7 +115,7 @@ void GNRiccatiSolver::changeNumberOfStages(int N Hi_.resize(N); Hi_inverse_.resize(N); - lv_.resize(N); + this->lv_.resize(N); this->L_.resize(N); this->x_sol_.resize(N + 1); @@ -158,9 +157,9 @@ void GNRiccatiSolver::computeCostToGo(size_t k) sv_[k] = p.qv_[k]; sv_[k].noalias() += p.A_[k].transpose() * sv_[k + 1]; sv_[k].noalias() += p.A_[k].transpose() * S_[k + 1] * p.b_[k]; - sv_[k].noalias() += this->L_[k].transpose() * Hi_[k] * lv_[k]; + sv_[k].noalias() += this->L_[k].transpose() * Hi_[k] * this->lv_[k]; sv_[k].noalias() += this->L_[k].transpose() * gv_[k]; - sv_[k].noalias() += G_[k].transpose() * lv_[k]; + sv_[k].noalias() += G_[k].transpose() * this->lv_[k]; } @@ -226,7 +225,7 @@ void GNRiccatiSolver::designController(size_t k) this->L_[k].noalias() = Hi_inverse_[k].template selfadjointView() * G_[k]; // calculate FF update - lv_[k].noalias() = Hi_inverse_[k].template selfadjointView() * gv_[k]; + this->lv_[k].noalias() = Hi_inverse_[k].template selfadjointView() * gv_[k]; } else { @@ -258,7 +257,7 @@ void GNRiccatiSolver::designController(size_t k) this->L_[k].noalias() = Hi_inverse_[k] * G_[k]; // calculate FF update - lv_[k].noalias() = Hi_inverse_[k] * gv_[k]; + this->lv_[k].noalias() = Hi_inverse_[k] * gv_[k]; } } diff --git a/ct_optcon/include/ct/optcon/solver/lqp/GNRiccatiSolver.hpp b/ct_optcon/include/ct/optcon/solver/lqp/GNRiccatiSolver.hpp index c59b49759..c6d59a1e5 100644 --- a/ct_optcon/include/ct/optcon/solver/lqp/GNRiccatiSolver.hpp +++ b/ct_optcon/include/ct/optcon/solver/lqp/GNRiccatiSolver.hpp @@ -44,8 +44,6 @@ class GNRiccatiSolver : public LQOCSolver GNRiccatiSolver(int N); - virtual ~GNRiccatiSolver(); - virtual void solve() override; virtual void initializeAndAllocate() override; @@ -54,13 +52,11 @@ class GNRiccatiSolver : public LQOCSolver virtual void configure(const NLOptConSettings& settings) override; - //! compute the state and control updates. - /*! - * The GNRiccati solver needs this method in order to compute the state and control solutions after the Riccati backward pass. - * - * \warning You need to call this method at the right place if you're using solveSingleStage() by yourself. - */ - virtual void extractLQSolution() override; + virtual void computeStatesAndControls() override; + + virtual void computeFeedbackMatrices() override; + + virtual void compute_lv() override; virtual SCALAR getSmallestEigenvalue() override; @@ -91,8 +87,6 @@ class GNRiccatiSolver : public LQOCSolver ControlMatrixArray Hi_inverse_; ControlMatrix H_corrFix_; - ControlVectorArray lv_; - StateVectorArray sv_; StateMatrixArray S_; diff --git a/ct_optcon/include/ct/optcon/solver/lqp/HPIPMInterface-impl.hpp b/ct_optcon/include/ct/optcon/solver/lqp/HPIPMInterface-impl.hpp index be2b2b6fe..b8b84b8b0 100644 --- a/ct_optcon/include/ct/optcon/solver/lqp/HPIPMInterface-impl.hpp +++ b/ct_optcon/include/ct/optcon/solver/lqp/HPIPMInterface-impl.hpp @@ -11,31 +11,35 @@ namespace ct { namespace optcon { template -HPIPMInterface::HPIPMInterface(const int N, const int nb, const int ng) - : N_(-1), nb_(1, nb), ng_(1, ng), x0_(nullptr), settings_(NLOptConSettings()) +HPIPMInterface::HPIPMInterface(const int N, const int nbu, const int nbx, const int ng) + : N_(-1), nbu_(1, nbu), nbx_(1, nbx), ng_(1, ng), settings_(NLOptConSettings()) { - // some zero variables hb0_.setZero(); hr0_.setZero(); // by default, set number of box and general constraints to zero if (N > 0) - setSolverDimensions(N, nb, ng); + setSolverDimensions(N, nbu, nbx, ng); configure(settings_); } - template HPIPMInterface::~HPIPMInterface() { + // todo is there memory that needs to be freed? } template -void HPIPMInterface::setSolverDimensions(const int N, const int nb, const int ng) +void HPIPMInterface::setSolverDimensions(const int N, + const int nbu, + const int nbx, + const int ng) { - nb_.resize(N + 1, nb); - ng_.resize(N + 1, ng); + nbu_.resize(N + 1, nbu); // todo this is bad design, is there no other way to propagate the number of constraints? + nbx_.resize(N + 1, nbx); // todo this is bad design, is there no other way to propagate the number of constraints? + ng_.resize(N + 1, ng); // todo this is bad design, is there no other way to propagate the number of constraints? + changeNumberOfStages(N); initializeAndAllocate(); } @@ -43,28 +47,52 @@ void HPIPMInterface::setSolverDimensions(const int N, co template void HPIPMInterface::initializeAndAllocate() { - int qp_size = ::d_memsize_ocp_qp(N_, nx_.data(), nu_.data(), nb_.data(), ng_.data()); - qp_mem_.resize(qp_size); - ::d_create_ocp_qp(N_, nx_.data(), nu_.data(), nb_.data(), ng_.data(), &qp_, qp_mem_.data()); - - int qp_sol_size = ::d_memsize_ocp_qp_sol(N_, nx_.data(), nu_.data(), nb_.data(), ng_.data()); - qp_sol_mem_.resize(qp_sol_size); - ::d_create_ocp_qp_sol(N_, nx_.data(), nu_.data(), nb_.data(), ng_.data(), &qp_sol_, qp_sol_mem_.data()); + // allocate ocp dimensions + dim_size_ = d_ocp_qp_dim_memsize(N_); + dim_mem_ = malloc(dim_size_); + d_ocp_qp_dim_create(N_, &dim_, dim_mem_); + d_ocp_qp_dim_set_all( + nx_.data(), nu_.data(), nbx_.data(), nbu_.data(), ng_.data(), nsbx_.data(), nsbu_.data(), nsg_.data(), &dim_); + + // allocate ocp qp + int qp_size = ::d_ocp_qp_memsize(&dim_); + qp_mem_ = malloc(qp_size); + ::d_ocp_qp_create(&dim_, &qp_, qp_mem_); + ::d_ocp_qp_set_all(hA_.data(), hB_.data(), hb_.data(), hQ_.data(), hS_.data(), hR_.data(), hq_.data(), hr_.data(), + hidxbx_.data(), hlbx_.data(), hubx_.data(), hidxbu_.data(), hlbu_.data(), hubu_.data(), // box constraints + hC_.data(), hD_.data(), hlg_.data(), hug_.data(), // gen constraints + hZl_.data(), hZu_.data(), hzl_.data(), hzu_.data(), hidxs_.data(), hlls_.data(), hlus_.data(), &qp_); + + // allocation for solution + int qp_sol_size = ::d_ocp_qp_sol_memsize(&dim_); + qp_sol_mem_ = malloc(qp_sol_size); + ::d_ocp_qp_sol_create(&dim_, &qp_sol_, qp_sol_mem_); + + // ipm arg + int ipm_arg_size = ::d_ocp_qp_ipm_arg_memsize(&dim_); + ipm_arg_mem_ = malloc(ipm_arg_size); + ::d_ocp_qp_ipm_arg_create(&dim_, &arg_, ipm_arg_mem_); + + ::d_ocp_qp_ipm_arg_set_default(mode_, &arg_); + ::d_ocp_qp_ipm_arg_set_iter_max(&settings_.lqoc_solver_settings.num_lqoc_iterations, &arg_); + + // create workspace + int ipm_size = ::d_ocp_qp_ipm_ws_memsize(&dim_, &arg_); + ipm_mem_ = malloc(ipm_size); + ::d_ocp_qp_ipm_ws_create(&dim_, &arg_, &workspace_, ipm_mem_); - int ipm_size = ::d_memsize_ipm_hard_ocp_qp(&qp_, &arg_); - ipm_mem_.resize(ipm_size); - ::d_create_ipm_hard_ocp_qp(&qp_, &arg_, &workspace_, ipm_mem_.data()); if (settings_.lqoc_solver_settings.lqoc_debug_print) { std::cout << "HPIPM allocating memory for QP with time horizon: " << N_ << std::endl; for (int i = 0; i < N_ + 1; i++) { - std::cout << "HPIPM stage " << i << ": (nx, nu, nb, ng) : (" << nx_[i] << ", " << nu_[i] << ", " << nb_[i] - << ", " << ng_[i] << ")" << std::endl; + std::cout << "HPIPM stage " << i << ": (nx, nu, nbu, nbx, ng) : (" << nx_[i] << ", " << nu_[i] << ", " + << nbu_[i] << ", " << nbx_[i] << ", " << ng_[i] << ")" << std::endl; } std::cout << "HPIPM qp_size: " << qp_size << std::endl; std::cout << "HPIPM qp_sol_size: " << qp_sol_size << std::endl; + std::cout << "HPIPM ipm_arg_size: " << ipm_arg_size << std::endl; std::cout << "HPIPM ipm_size: " << ipm_size << std::endl; } } @@ -74,12 +102,7 @@ template void HPIPMInterface::configure(const NLOptConSettings& settings) { settings_ = settings; - - arg_.iter_max = settings_.lqoc_solver_settings.num_lqoc_iterations; - - arg_.alpha_min = 1e-8; // todo review and make setting - arg_.mu_max = 1e-12; // todo review and make setting - arg_.mu0 = 2.0; // todo review and make setting + ::d_ocp_qp_ipm_arg_set_iter_max(&settings_.lqoc_solver_settings.num_lqoc_iterations, &arg_); } @@ -117,14 +140,19 @@ void HPIPMInterface::solve() d_print_mat(1, CONTROL_DIM, hr_[i], 1); } - printf("\nnb\n"); - std::cout << nb_[i] << std::endl; - printf("\nhidxb_\n"); - int_print_mat(1, nb_[i], hidxb_[i], 1); - printf("\nhd_lb_\n"); - d_print_mat(1, nb_[i], hd_lb_[i], 1); - printf("\nhd_ub_\n"); - d_print_mat(1, nb_[i], hd_ub_[i], 1); + printf("\nnbu\n"); + std::cout << nbu_[i] << std::endl; + printf("\nhlbu_\n"); + d_print_mat(1, nbu_[i], hlbu_[i], 1); + printf("\nhubu_\n"); + d_print_mat(1, nbu_[i], hubu_[i], 1); + + printf("\nnbx\n"); + std::cout << nbx_[i] << std::endl; + printf("\nhlbx_\n"); + d_print_mat(1, nbx_[i], hlbx_[i], 1); + printf("\nhubx_\n"); + d_print_mat(1, nbx_[i], hubx_[i], 1); printf("\nng\n"); std::cout << ng_[i] << std::endl; @@ -132,162 +160,161 @@ void HPIPMInterface::solve() d_print_mat(ng_[i], STATE_DIM, hC_[i], ng_[i]); printf("\nD\n"); d_print_mat(ng_[i], CONTROL_DIM, hD_[i], ng_[i]); - printf("\nhd_lg_\n"); - d_print_mat(1, ng_[i], hd_lg_[i], 1); - printf("\nhd_ug_\n"); - d_print_mat(1, ng_[i], hd_ug_[i], 1); + printf("\nhlg_\n"); + d_print_mat(1, ng_[i], hlg_[i], 1); + printf("\nhug_\n"); + d_print_mat(1, ng_[i], hug_[i], 1); } // end optional printout #endif // HPIPM_PRINT_MATRICES - // set pointers to optimal control problem - ::d_cvt_colmaj_to_ocp_qp(hA_.data(), hB_.data(), hb_.data(), hQ_.data(), hS_.data(), hR_.data(), hq_.data(), - hr_.data(), hidxb_.data(), hd_lb_.data(), hd_ub_.data(), hC_.data(), hD_.data(), hd_lg_.data(), hd_ug_.data(), - &qp_); // solve optimal control problem - ::d_solve_ipm2_hard_ocp_qp(&qp_, &qp_sol_, &workspace_); + ::d_ocp_qp_ipm_solve(&qp_, &qp_sol_, &arg_, &workspace_); + ::d_ocp_qp_ipm_get_status(&workspace_, &hpipm_status_); + + isLrInvComputed_ = false; // display iteration summary if (settings_.lqoc_solver_settings.lqoc_debug_print) { + printf("\nHPIPM returned with flag %i.\n", hpipm_status_); + if (hpipm_status_ == 0) + { + printf("\n -> QP solved!\n"); + } + else if (hpipm_status_ == 1) + { + printf("\n -> Solver failed! Maximum number of iterations reached\n"); + } + else if (hpipm_status_ == 2) + { + printf("\n -> Solver failed! Minimum step length reached\n"); + } + else if (hpipm_status_ == 2) + { + printf("\n -> Solver failed! NaN in computations\n"); + } + else + { + printf("\n -> Solver failed! Unknown return flag\n"); + } printf("\nipm iter = %d\n", workspace_.iter); printf("\nalpha_aff\tmu_aff\t\tsigma\t\talpha\t\tmu\n"); d_print_e_tran_mat(5, workspace_.iter, workspace_.stat, 5); + } +} - printSolution(); +template +void HPIPMInterface::computeStatesAndControls() +{ + // extract solution for x and u + for (int ii = 0; ii < N_; ii++) + { + Eigen::Matrix u_sol; + ::d_ocp_qp_sol_get_u(ii, &qp_sol_, this->u_sol_[ii].data()); + } + for (int ii = 0; ii <= N_; ii++) + { + Eigen::Matrix x_sol; + ::d_ocp_qp_sol_get_x(ii, &qp_sol_, this->x_sol_[ii].data()); } - // convert optimal control problem solution to standard column-major representation - ::d_cvt_ocp_qp_sol_to_colmaj(&qp_, &qp_sol_, u_.data(), x_.data(), pi_.data(), lam_lb_.data(), lam_ub_.data(), - lam_lg_.data(), lam_ug_.data()); + // display iteration summary + if (settings_.lqoc_solver_settings.lqoc_debug_print) + { + printSolution(); + } +} - designFeedback(); +template +void HPIPMInterface::computeLrInvArray() +{ + // extract data which is mandatory for computing either feedback or iLQR feedforward + Eigen::Matrix Lr; + for (int i = 0; i < N_; i++) + { + ::d_ocp_qp_ipm_get_ric_Lr(i, &workspace_, Lr.data()); + Lr_inv_[i] = (Lr.template triangularView()) + .solve(Eigen::Matrix::Identity()); + } + isLrInvComputed_ = true; } template -void HPIPMInterface::designFeedback() +void HPIPMInterface::computeFeedbackMatrices() { + if (isLrInvComputed_ == false) + computeLrInvArray(); // update Lr_inv_ first + LQOCProblem& p = *this->lqocProblem_; this->L_.resize(p.getNumberOfStages()); - // for stage 0, HPIPM does not provide feedback, so we have to construct it + // for steps k=1,...,N-1 we can just read Ls, Lr_inv already has been computed + Eigen::Matrix Ls; - // step 1: reconstruct H[0] - Eigen::Matrix Lr; - ::d_cvt_strmat2mat(Lr.rows(), Lr.cols(), &workspace_.L[0], 0, 0, Lr.data(), Lr.rows()); - Eigen::Matrix H; - H = Lr.template triangularView() * Lr.transpose(); // Lr is cholesky of H + for (int i = 1; i < this->lqocProblem_->getNumberOfStages(); i++) + { + ::d_ocp_qp_ipm_get_ric_Ls(i, &workspace_, Ls.data()); + this->L_[i] = -(Ls * Lr_inv_[i]).transpose(); + } - // step2: reconstruct S[1] - Eigen::Matrix Lq; - ::d_cvt_strmat2mat(Lq.rows(), Lq.cols(), &workspace_.L[1], control_dim, control_dim, Lq.data(), Lq.rows()); - Eigen::Matrix S; - S = Lq.template triangularView() * Lq.transpose(); // Lq is cholesky of S + // for stage k=0, HPIPM does not have meaningful entries for Ls, so we have to manually design the feedback + // retrieve Riccati matrix for stage 1 (we call it S, others call it P) + Eigen::Matrix S1; + ::d_ocp_qp_ipm_get_ric_P(1, &workspace_, S1.data()); - // step3: compute G[0] + // step2: compute G[0] Eigen::Matrix G; G = p.P_[0]; - G.noalias() += p.B_[0].transpose() * S * p.A_[0]; + G.noalias() += p.B_[0].transpose() * S1 * p.A_[0]; - // step4: compute K[0] - this->L_[0] = (-H.inverse() * G); // \todo use Lr here instead of H! + // step3: compute K[0] = H.inverse() * G + this->L_[0] = (-Lr_inv_[0].transpose() * Lr_inv_[0] * G); +} - // for all other steps we can just read Ls - Eigen::Matrix Ls; - for (int i = 1; i < this->lqocProblem_->getNumberOfStages(); i++) +template +void HPIPMInterface::compute_lv() +{ + if (this->lqocProblem_->isConstrained()) + throw std::runtime_error( + "Retrieving lv is not compatible with constraints in HPIPM. Switch to different algorithm, e.g. GNMS, " + "which does not require lv"); + + if (isLrInvComputed_ == false) + computeLrInvArray(); // update Lr_inv_ first + + Eigen::Matrix lr; + for (int i = 0; i < this->lqocProblem_->getNumberOfStages(); i++) { - ::d_cvt_strmat2mat(Lr.rows(), Lr.cols(), &workspace_.L[i], 0, 0, Lr.data(), Lr.rows()); - ::d_cvt_strmat2mat(Ls.rows(), Ls.cols(), &workspace_.L[i], Lr.rows(), 0, Ls.data(), Ls.rows()); - this->L_[i] = (-Ls * Lr.partialPivLu().inverse()).transpose(); + ::d_ocp_qp_ipm_get_ric_lr(i, &workspace_, lr.data()); + this->lv_[i] = -Lr_inv_[i].transpose() * lr; } } - template void HPIPMInterface::printSolution() { +#ifdef HPIPM_PRINT_MATRICES int ii; - ::d_cvt_ocp_qp_sol_to_colmaj(&qp_, &qp_sol_, u_.data(), x_.data(), pi_.data(), lam_lb_.data(), lam_ub_.data(), - lam_lg_.data(), lam_ug_.data()); - - printf("\nsolution\n\n"); - printf("\nu\n"); - for (ii = 0; ii <= N_; ii++) - d_print_mat(1, nu_[ii], u_[ii], 1); - printf("\nx\n"); - for (ii = 0; ii <= N_; ii++) - d_print_mat(1, nx_[ii], x_[ii], 1); - -#ifdef HPIPM_PRINT_MATRICES - printf("\npi\n"); + std::cout << "Solution for u: " << std::endl; for (ii = 0; ii < N_; ii++) - d_print_mat(1, nx_[ii + 1], pi_[ii], 1); - printf("\nlam_lb\n"); - for (ii = 0; ii <= N_; ii++) - d_print_mat(1, nb_[ii], lam_lb_[ii], 1); - printf("\nlam_ub\n"); - for (ii = 0; ii <= N_; ii++) - d_print_mat(1, nb_[ii], lam_ub_[ii], 1); - printf("\nlam_lg\n"); - for (ii = 0; ii <= N_; ii++) - d_print_mat(1, ng_[ii], lam_lg_[ii], 1); - printf("\nlam_ug\n"); - for (ii = 0; ii <= N_; ii++) - d_print_mat(1, ng_[ii], lam_ug_[ii], 1); - - printf("\nt_lb\n"); - for (ii = 0; ii <= N_; ii++) - d_print_mat(1, nb_[ii], (qp_sol_.t_lb + ii)->pa, 1); - printf("\nt_ub\n"); - for (ii = 0; ii <= N_; ii++) - d_print_mat(1, nb_[ii], (qp_sol_.t_ub + ii)->pa, 1); - printf("\nt_lg\n"); - for (ii = 0; ii <= N_; ii++) - d_print_mat(1, ng_[ii], (qp_sol_.t_lg + ii)->pa, 1); - printf("\nt_ug\n"); - for (ii = 0; ii <= N_; ii++) - d_print_mat(1, ng_[ii], (qp_sol_.t_ug + ii)->pa, 1); + { + std::cout << this->u_sol_[ii].transpose() << std::endl; + } - printf("\nresiduals\n\n"); - printf("\nres_g\n"); + std::cout << "Solution for x: " << std::endl; for (ii = 0; ii <= N_; ii++) - d_print_e_mat(1, nu_[ii] + nx_[ii], (workspace_.res_g + ii)->pa, 1); - printf("\nres_b\n"); - for (ii = 0; ii < N_; ii++) - d_print_e_mat(1, nx_[ii + 1], (workspace_.res_b + ii)->pa, 1); - printf("\nres_m_lb\n"); - for (ii = 0; ii <= N_; ii++) - d_print_e_mat(1, nb_[ii], (workspace_.res_m_lb + ii)->pa, 1); - printf("\nres_m_ub\n"); - for (ii = 0; ii <= N_; ii++) - d_print_e_mat(1, nb_[ii], (workspace_.res_m_ub + ii)->pa, 1); - printf("\nres_m_lg\n"); - for (ii = 0; ii <= N_; ii++) - d_print_e_mat(1, ng_[ii], (workspace_.res_m_lg + ii)->pa, 1); - printf("\nres_m_ug\n"); - for (ii = 0; ii <= N_; ii++) - d_print_e_mat(1, ng_[ii], (workspace_.res_m_ug + ii)->pa, 1); - printf("\nres_d_lb\n"); - for (ii = 0; ii <= N_; ii++) - d_print_e_mat(1, nb_[ii], (workspace_.res_d_lb + ii)->pa, 1); - printf("\nres_d_ub\n"); - for (ii = 0; ii <= N_; ii++) - d_print_e_mat(1, nb_[ii], (workspace_.res_d_ub + ii)->pa, 1); - printf("\nres_d_lg\n"); - for (ii = 0; ii <= N_; ii++) - d_print_e_mat(1, ng_[ii], (workspace_.res_d_lg + ii)->pa, 1); - printf("\nres_d_ug\n"); - for (ii = 0; ii <= N_; ii++) - d_print_e_mat(1, ng_[ii], (workspace_.res_d_ug + ii)->pa, 1); - printf("\nres_mu\n"); - printf("\n%e\n\n", workspace_.res_mu); + { + std::cout << this->x_sol_[ii].transpose() << std::endl; + } #endif // HPIPM_PRINT_MATRICES - printf("\nipm iter = %d\n", workspace_.iter); + int iter; + ::d_ocp_qp_ipm_get_iter(&workspace_, &iter); printf("\nalpha_aff\tmu_aff\t\tsigma\t\talpha\t\tmu\n"); - ::d_print_e_tran_mat(5, workspace_.iter, workspace_.stat, 5); + ::d_print_mat(5, iter, workspace_.stat, 5); } @@ -298,65 +325,75 @@ void HPIPMInterface::setProblemImpl( // check if the number of stages N changed and adapt problem dimensions bool nStagesChanged = changeNumberOfStages(lqocProblem->getNumberOfStages()); - // WARNING: the allocation should in practice not have to happen during the loop. // If possible, prefer receding horizon MPC problems. // If the number of stages has changed, however, the problem needs to be re-built: if (nStagesChanged) { // update constraint configuration in case the horizon length has changed. - if (lqocProblem->isBoxConstrained()) - configureBoxConstraints(lqocProblem); + if (lqocProblem->isInputBoxConstrained()) + configureInputBoxConstraints(lqocProblem); + + if (lqocProblem->isStateBoxConstrained()) + configureStateBoxConstraints(lqocProblem); if (lqocProblem->isGeneralConstrained()) configureGeneralConstraints(lqocProblem); } // setup unconstrained part of problem - setupCostAndDynamics(lqocProblem->x_, lqocProblem->u_, lqocProblem->A_, lqocProblem->B_, lqocProblem->b_, - lqocProblem->P_, lqocProblem->qv_, lqocProblem->Q_, lqocProblem->rv_, lqocProblem->R_); - + setupCostAndDynamics(lqocProblem->A_, lqocProblem->B_, lqocProblem->b_, lqocProblem->P_, lqocProblem->qv_, + lqocProblem->Q_, lqocProblem->rv_, lqocProblem->R_); if (nStagesChanged) - { initializeAndAllocate(); + else + { + // we need to call the setters to transform our data into HPIPM interal structures + ::d_ocp_qp_set_all(hA_.data(), hB_.data(), hb_.data(), hQ_.data(), hS_.data(), hR_.data(), hq_.data(), + hr_.data(), hidxbx_.data(), hlbx_.data(), hubx_.data(), hidxbu_.data(), hlbu_.data(), hubu_.data(), + hC_.data(), hD_.data(), hlg_.data(), hug_.data(), hZl_.data(), hZu_.data(), hzl_.data(), hzu_.data(), + hidxs_.data(), hlls_.data(), hlus_.data(), &qp_); } } template -void HPIPMInterface::configureBoxConstraints( +void HPIPMInterface::configureInputBoxConstraints( + std::shared_ptr> lqocProblem) +{ + // stages 1 to N + for (int i = 0; i < N_; i++) + { + nbu_[i] = lqocProblem->nbu_[i]; + + // set pointers to box constraint boundaries and sparsity pattern + hlbu_[i] = lqocProblem->u_lb_[i].data(); + hubu_[i] = lqocProblem->u_ub_[i].data(); + hidxbu_[i] = lqocProblem->u_I_[i].data(); + } +} + + +template +void HPIPMInterface::configureStateBoxConstraints( std::shared_ptr> lqocProblem) { // stages 1 to N for (int i = 0; i < N_ + 1; i++) { - nb_[i] = lqocProblem->nb_[i]; + nbx_[i] = lqocProblem->nbx_[i]; // set pointers to box constraint boundaries and sparsity pattern - hd_lb_[i] = lqocProblem->ux_lb_[i].data(); - hd_ub_[i] = lqocProblem->ux_ub_[i].data(); - hidxb_[i] = lqocProblem->ux_I_[i].data(); + hlbx_[i] = lqocProblem->x_lb_[i].data(); + hubx_[i] = lqocProblem->x_ub_[i].data(); + hidxbx_[i] = lqocProblem->x_I_[i].data(); // first stage requires special treatment as state is not a decision variable if (i == 0) { - nb_[i] = 0; - for (int j = 0; j < lqocProblem->nb_[i]; j++) - { - if (lqocProblem->ux_I_[i](j) < CONTROL_DIM) - nb_[i]++; // adapt number of constraints such that only controls are listed as decision vars - else - break; - } + nbx_[i] = 0; } - - // TODO clarify with Gianluca if we need to reset the lagrange multiplier - // before warmstarting (potentially wrong warmstart for the lambdas) - - // direct pointers of lagrange mult to corresponding containers - lam_lb_[i] = cont_lam_lb_[i].data(); - lam_ub_[i] = cont_lam_ub_[i].data(); } } @@ -366,51 +403,41 @@ void HPIPMInterface::configureGeneralConstraints( std::shared_ptr> lqocProblem) { // HPIPM-specific correction for first-stage general constraint bounds - hd_lg_0_Eigen_ = lqocProblem->d_lb_[0] - lqocProblem->C_[0] * lqocProblem->x_[0]; - hd_ug_0_Eigen_ = lqocProblem->d_ub_[0] - lqocProblem->C_[0] * lqocProblem->x_[0]; + hd_lg_0_Eigen_ = lqocProblem->d_lb_[0]; // - lqocProblem->C_[0] * x0; // uncommented since x0=0 + hd_ug_0_Eigen_ = lqocProblem->d_ub_[0]; // - lqocProblem->C_[0] * x0; // uncommented since x0=0 + + assert(ng_.size() == ((size_t)N_ + 1)); for (int i = 0; i < N_ + 1; i++) // (includes the terminal stage) { - // check dimensions - assert(lqocProblem->d_lb_[i].rows() == lqocProblem->d_ub_[i].rows()); - assert(lqocProblem->d_lb_[i].rows() == lqocProblem->C_[i].rows()); - assert(lqocProblem->d_lb_[i].rows() == lqocProblem->D_[i].rows()); - assert(lqocProblem->C_[i].cols() == STATE_DIM); - assert(lqocProblem->D_[i].cols() == CONTROL_DIM); - // get the number of constraints ng_[i] = lqocProblem->ng_[i]; + lqocProblem->C_[i].resize(lqocProblem->ng_[i], STATE_DIM); + lqocProblem->D_[i].resize(lqocProblem->ng_[i], CONTROL_DIM); + lqocProblem->d_lb_[i].resize(lqocProblem->ng_[i], 1); + lqocProblem->d_ub_[i].resize(lqocProblem->ng_[i], 1); + // set pointers to hpipm-style box constraint boundaries and sparsity pattern if (i == 0) { - hd_lg_[i] = hd_lg_0_Eigen_.data(); - hd_ug_[i] = hd_ug_0_Eigen_.data(); + hlg_[i] = hd_lg_0_Eigen_.data(); + hug_[i] = hd_ug_0_Eigen_.data(); } else { - hd_lg_[i] = lqocProblem->d_lb_[i].data(); - hd_ug_[i] = lqocProblem->d_ub_[i].data(); + hlg_[i] = lqocProblem->d_lb_[i].data(); + hug_[i] = lqocProblem->d_ub_[i].data(); } + hC_[i] = lqocProblem->C_[i].data(); hD_[i] = lqocProblem->D_[i].data(); - - // TODO clarify with Gianluca if we need to reset the lagrange multiplier - // before warmstarting (potentially wrong warmstart for the lambdas) - - // direct pointers of lagrange mult to corresponding containers - cont_lam_lg_[i].resize(ng_[i]); // todo avoid dynamic allocation (e.g. by defining a max. constraint dim) - cont_lam_ug_[i].resize(ng_[i]); // todo avoid dynamic allocation (e.g. by defining a max. constraint dim) - lam_lg_[i] = cont_lam_lg_[i].data(); - lam_ug_[i] = cont_lam_ug_[i].data(); } } template -void HPIPMInterface::setupCostAndDynamics(StateVectorArray& x, - ControlVectorArray& u, - StateMatrixArray& A, +void HPIPMInterface::setupCostAndDynamics(StateMatrixArray& A, StateControlMatrixArray& B, StateVectorArray& b, FeedbackArray& P, @@ -422,17 +449,20 @@ void HPIPMInterface::setupCostAndDynamics(StateVectorArr if (N_ == -1) throw std::runtime_error("Time horizon not set, please set it first"); - // assign data for LQ problem + this->x_sol_[0].setZero(); // fixed intitial value problem (increment is zero) - // set pointer to the initial state - this->x_sol_[0] = x[0]; - x0_ = x[0].data(); + // IMPORTANT: for hb_ and hr_, we need a HPIPM-specific correction for the first stage + hb0_ = b[0]; // + A[0] * x0; // uncommented since x0 = 0 in diff formulation + hr0_ = rv[0]; // + P[0] * x0; // uncommented since x0 = 0 in diff formulation + // assign data for LQ problem for (int i = 0; i < N_; i++) { hA_[i] = A[i].data(); hB_[i] = B[i].data(); - hb_[i] = b[i].data(); + + if (i > 0) + hb_[i] = b[i].data(); // do not mutate pointers for init stage } for (int i = 0; i < N_; i++) @@ -441,21 +471,14 @@ void HPIPMInterface::setupCostAndDynamics(StateVectorArr hS_[i] = P[i].data(); hR_[i] = R[i].data(); hq_[i] = qv[i].data(); - hr_[i] = rv[i].data(); + + if (i > 0) + hr_[i] = rv[i].data(); // do not mutate pointers for init stage } // terminal stage hQ_[N_] = Q[N_].data(); hq_[N_] = qv[N_].data(); - - // IMPORTANT: for hb_ and hr_, we need a HPIPM-specific correction for the first stage - hb0_ = b[0] + A[0] * x[0]; - hr0_ = rv[0] + P[0] * x[0]; - hb_[0] = hb0_.data(); - hr_[0] = hr0_.data(); - - // reset lqocProblem pointer, will get set in Base class if needed - this->lqocProblem_ = nullptr; } @@ -467,16 +490,26 @@ bool HPIPMInterface::changeNumberOfStages(int N) N_ = N; - nx_.resize(N_ + 1, STATE_DIM); // initialize number of states per stage + // resize control input variable counter + if (nu_.size() > 0) + nu_.back() = CONTROL_DIM; // avoid error in case of increasing horizon nu_.resize(N_ + 1, CONTROL_DIM); // initialize number of control inputs per stage - nb_.resize(N_ + 1, nb_.back()); // initialize number of box constraints per stage - ng_.resize(N_ + 1, ng_.back()); // initialize number of general constraints per stage + nu_[N_] = 0; // last input is not a decision variable + + nx_.resize(N_ + 1, STATE_DIM); // initialize number of states per stage + nx_[0] = 0; // initial state is not a decision variable but given + // resize the containers for the affine system dynamics approximation hA_.resize(N_); hB_.resize(N_); hb_.resize(N_); + this->x_sol_.resize(N_ + 1); + this->u_sol_.resize(N_); + this->lv_.resize(N_); + this->L_.resize(N_); + // resize the containers for the LQ cost approximation hQ_.resize(N_ + 1); hS_.resize(N_ + 1); @@ -484,72 +517,51 @@ bool HPIPMInterface::changeNumberOfStages(int N) hq_.resize(N_ + 1); hr_.resize(N_ + 1); - hd_lb_.resize(N_ + 1); - hd_ub_.resize(N_ + 1); - hidxb_.resize(N_ + 1); - hd_lg_.resize(N_ + 1); - hd_ug_.resize(N_ + 1); + // initialize number of box constraints per stage + nbu_.resize(N_ + 1, nbu_.back()); + nbx_.resize(N_ + 1, nbx_.back()); + hidxbx_.resize(N_ + 1); + hidxbu_.resize(N_ + 1); + hlbx_.resize(N_ + 1, 0); + hubx_.resize(N_ + 1, 0); + hlbu_.resize(N_ + 1, 0); + hubu_.resize(N_ + 1, 0); + + // initialize number of gen constraints per stage + ng_.resize(N_ + 1, 0); + hlg_.resize(N_ + 1, 0); + hug_.resize(N_ + 1, 0); hC_.resize(N_ + 1); hD_.resize(N_ + 1); - u_.resize(N_ + 1); - x_.resize(N_ + 1); - pi_.resize(N_); - hpi_.resize(N_); - this->x_sol_.resize(N_ + 1); - this->u_sol_.resize(N_); - - lam_lb_.resize(N_ + 1); - lam_ub_.resize(N_ + 1); - lam_lg_.resize(N_ + 1); - lam_ug_.resize(N_ + 1); - cont_lam_lb_.resize(N_ + 1); - cont_lam_ub_.resize(N_ + 1); - cont_lam_lg_.resize(N_ + 1); - cont_lam_ug_.resize(N_ + 1); + // currently ignored stuff (resized anyways) + nsbx_.resize(N_ + 1, 0); // no softened state box constraints + nsbu_.resize(N_ + 1, 0); // no softened input box constraints + nsg_.resize(N_ + 1, 0); // no softened general constraints - for (int i = 0; i < N_; i++) - { - // first state and last input are not optimized - x_[i + 1] = this->x_sol_[i + 1].data(); - u_[i] = this->u_sol_[i].data(); - } - for (int i = 0; i < N_; i++) - { - pi_[i] = hpi_[i].data(); - } + hZl_.resize(N_ + 1, 0); + hZu_.resize(N_ + 1, 0); + hzl_.resize(N_ + 1, 0); + hzu_.resize(N_ + 1, 0); - hS_[N_] = nullptr; - hR_[N_] = nullptr; - hr_[N_] = nullptr; + hidxs_.resize(N_ + 1, 0); - hb_[0] = nullptr; - hr_[0] = nullptr; + hlls_.resize(N_ + 1, 0); + hlus_.resize(N_ + 1, 0); - ct::core::StateVectorArray hx; - ct::core::ControlVectorArray hu; + Lr_inv_.resize(N_); - // initial state is not a decision variable but given - nx_[0] = 0; + // assignments that stay constant despite varying problem impl data + hb_[0] = hb0_.data(); + hr_[0] = hr0_.data(); - // last input is not a decision variable - nu_[N] = 0; + hS_[N_] = nullptr; + hR_[N_] = nullptr; + hr_[N_] = nullptr; return true; } - -template -void HPIPMInterface::d_zeros(double** pA, int row, int col) -{ - *pA = (double*)malloc((row * col) * sizeof(double)); - double* A = *pA; - int i; - for (i = 0; i < row * col; i++) - A[i] = 0.0; -} - - template void HPIPMInterface::d_print_mat(int m, int n, double* A, int lda) { @@ -566,38 +578,6 @@ void HPIPMInterface::d_print_mat(int m, int n, double* A } -template -void HPIPMInterface::d_print_tran_mat(int row, int col, double* A, int lda) -{ - int i, j; - for (j = 0; j < col; j++) - { - for (i = 0; i < row; i++) - { - printf("%9.5f ", A[i + lda * j]); - } - printf("\n"); - } - printf("\n"); -} - - -template -void HPIPMInterface::d_print_e_mat(int m, int n, double* A, int lda) -{ - int i, j; - for (i = 0; i < m; i++) - { - for (j = 0; j < n; j++) - { - printf("%e\t", A[i + lda * j]); - } - printf("\n"); - } - printf("\n"); -} - - template void HPIPMInterface::d_print_e_tran_mat(int row, int col, double* A, int lda) { @@ -615,18 +595,14 @@ void HPIPMInterface::d_print_e_tran_mat(int row, int col template -void HPIPMInterface::int_print_mat(int row, int col, int* A, int lda) +const ct::core::ControlVectorArray& HPIPMInterface::get_lv() { - int i, j; - for (i = 0; i < row; i++) - { - for (j = 0; j < col; j++) - { - printf("%d ", A[i + lda * j]); - } - printf("\n"); - } - printf("\n"); + if (this->lqocProblem_->isConstrained()) + throw std::runtime_error( + "Retrieving lv is not compatible with constraints in HPIPM. Switch to different algorithm, e.g. GNMS, " + "which does not require lv"); + + return this->lv_; } } // namespace optcon diff --git a/ct_optcon/include/ct/optcon/solver/lqp/HPIPMInterface.hpp b/ct_optcon/include/ct/optcon/solver/lqp/HPIPMInterface.hpp index e7d840e71..85609d321 100644 --- a/ct_optcon/include/ct/optcon/solver/lqp/HPIPMInterface.hpp +++ b/ct_optcon/include/ct/optcon/solver/lqp/HPIPMInterface.hpp @@ -11,16 +11,15 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #include #include -#include -#include -#include #include -#include +#include extern "C" { #include #include -#include +#include +#include +#include } #include @@ -31,6 +30,8 @@ namespace optcon { /*! * This class implements an interface to the HPIPM solver + * + * \note see also the official hpipm repo, i.e. the discussion in https://github.com/giaf/hpipm/issues/76 * * \warning in order to allow for an efficient implementation of constrained MPC, * the configuration of the box and general constraints must be done independently @@ -60,12 +61,11 @@ class HPIPMInterface : public LQOCSolver using constr_vec_t = Eigen::Matrix; using constr_vec_array_t = ct::core::DiscreteArray; - //! typedef a container for a sparsity pattern vector for box constraints using box_constr_sparsity_t = Eigen::Matrix; //! constructor - HPIPMInterface(const int N = -1, const int nb = 0, const int ng = 0); + HPIPMInterface(const int N = -1, const int nbu = 0, const int nbx = 0, const int ng = 0); //! destructor virtual ~HPIPMInterface(); @@ -74,12 +74,17 @@ class HPIPMInterface : public LQOCSolver void solve() override; - void designFeedback(); + virtual void computeStatesAndControls() override; + virtual void computeFeedbackMatrices() override; + virtual void compute_lv() override; void printSolution(); //! brief setup and configure the box constraints - virtual void configureBoxConstraints(std::shared_ptr> lqocProblem) override; + virtual void configureInputBoxConstraints( + std::shared_ptr> lqocProblem) override; + virtual void configureStateBoxConstraints( + std::shared_ptr> lqocProblem) override; //! brief setup and configure the general (in)equality constraints virtual void configureGeneralConstraints(std::shared_ptr> lqocProblem) override; @@ -98,8 +103,11 @@ class HPIPMInterface : public LQOCSolver */ virtual void initializeAndAllocate() override; + //! override this method to catch corner case with lv being incompatible with constraints + virtual const ct::core::ControlVectorArray& get_lv() override; + private: - void setSolverDimensions(const int N, const int nb = 0, const int ng = 0); + void setSolverDimensions(const int N, const int nbu = 0, const int nbx = 0, const int ng = 0); /*! * @brief set problem implementation for HPIPM @@ -129,9 +137,7 @@ class HPIPMInterface : public LQOCSolver * * \warning To achieve compatibility with HPIPM, this method needs to perform a change of coordinates for certain problem variables in the first stage. */ - void setupCostAndDynamics(StateVectorArray& x, - ControlVectorArray& u, - StateMatrixArray& A, + void setupCostAndDynamics(StateMatrixArray& A, StateControlMatrixArray& B, StateVectorArray& b, FeedbackArray& P, @@ -146,125 +152,99 @@ class HPIPMInterface : public LQOCSolver */ bool changeNumberOfStages(int N); - //! creates a zero matrix - void d_zeros(double** pA, int row, int col); + /** + * @brief compute the array of inverses of the Lr-matrix from the cholesky factorization of the Hessian + * @note is put into separate function since triggered by request and flagged by bool + */ + void computeLrInvArray(); + bool isLrInvComputed_; //! prints a matrix in column-major format void d_print_mat(int m, int n, double* A, int lda); - //! prints a matrix in column-major format (exponential notation) - void d_print_e_mat(int m, int n, double* A, int lda); - - //! prints the transposed of a matrix in column-major format (exponential notation) + //! prints the transposed of a matrix in column-major format, exp notation void d_print_e_tran_mat(int row, int col, double* A, int lda); - //! prints the transposed of a matrix in column-major format - void d_print_tran_mat(int row, int col, double* A, int lda); - - //! prints a matrix in column-major format - void int_print_mat(int row, int col, int* A, int lda); - //! horizon length int N_; - //! number of states per stage - std::vector nx_; - //! number of inputs per stage - std::vector nu_; - - //! number of box constraints per stage - std::vector nb_; - //! number of general constraints per stage - std::vector ng_; - - //! pointer to initial state - double* x0_; - - //! system state sensitivities - std::vector hA_; - //! system input sensitivities - std::vector hB_; - //! system offset term - std::vector hb_; - //! intermediate container for intuitive transcription of first stage - Eigen::Matrix hb0_; - - - //! pure state penalty hessian - std::vector hQ_; - //! state-control cross-terms - std::vector hS_; - //! pure control penalty hessian - std::vector hR_; - //! pure state penalty jacobian - std::vector hq_; - //! pure control penalty jacobian - std::vector hr_; - //! intermediate container for intuitive transcription of first stage - Eigen::Matrix hr0_; - - - //! pointer to lower box constraint boundary - std::vector hd_lb_; - //! pointer to upper box constraint boundary - std::vector hd_ub_; - //! pointer to sparsity pattern for box constraints - std::vector hidxb_; - - //! lower general constraint boundary - std::vector hd_lg_; - //! upper general constraint boundary - std::vector hd_ug_; - //! general constraint jacobians w.r.t. states - std::vector hC_; - //! general constraint jacobians w.r.t. controls (presumably) - std::vector hD_; + std::vector nx_; //! number of states per stage + std::vector nu_; //! number of inputs per stage + + std::vector nbu_; //! number of input box constraints per stage + std::vector nbx_; //! number of state box constraints per stage + + std::vector ng_; //! number of general constraints per stage + + std::vector nsbx_; // number of softed constraints on state box constraints + std::vector nsbu_; // number of softed constraints on input box constraints + std::vector nsg_; // number of softed constraints on general constraints + + std::vector hA_; //! system state sensitivities + std::vector hB_; //! system input sensitivities + std::vector hb_; //! system offset term + Eigen::Matrix hb0_; //! intermediate container for intuitive transcription of first stage + + std::vector hQ_; //! pure state penalty hessian + std::vector hS_; //! state-control cross-terms + std::vector hR_; //! pure control penalty hessian + std::vector hq_; //! pure state penalty jacobian + std::vector hr_; //! pure control penalty jacobian + Eigen::Matrix hr0_; //! local Eigen container for first stage transcription + + std::vector hlbx_; //! pointer to lower state box constraint boundary + std::vector hubx_; //! pointer to upper state box constraint boundary + std::vector hlbu_; //! pointer to lower input box constraint boundary + std::vector hubu_; //! pointer to upper input box constraint boundary + + std::vector hidxbx_; //! pointer to sparsity pattern for box constraints in x + std::vector hidxbu_; //! pointer to sparsity pattern for box constraints in u + + std::vector hlg_; //! lower general constraint boundary + std::vector hug_; //! upper general constraint boundary + std::vector hC_; //! general constraint jacobians w.r.t. states + std::vector hD_; //! general constraint jacobians w.r.t. controls + // local vars for constraint bounds for statge k=0, which need to be different by HPIPM convention Eigen::VectorXd hd_lg_0_Eigen_; Eigen::VectorXd hd_ug_0_Eigen_; + std::vector hZl_; // todo what are those quantities? (related to soft constraints?) + std::vector hZu_; + std::vector hzl_; + std::vector hzu_; + std::vector hidxs_; + std::vector hlls_; + std::vector hlus_; + + // cached data for efficiency + ct::core::DiscreteArray> Lr_inv_; // inv of cholesky matrix of hessian H - /* - * SOLUTION variables - */ - //! optimal control trajectory - std::vector u_; - //! optimal state trajectory - std::vector x_; - //! @todo what is this ? - std::vector pi_; - //! ptr to lagrange multiplier box-constraint lower - std::vector lam_lb_; - //! ptr to lagrange multiplier box-constraint upper - std::vector lam_ub_; - //! ptr to lagrange multiplier general-constraint lower - std::vector lam_lg_; - //! ptr to lagrange multiplier general-constraint upper - std::vector lam_ug_; - - //! container lagr. mult. box-constr. lower - ct::core::DiscreteArray> cont_lam_lb_; - //! container lagr. mult. box-constr. upper - ct::core::DiscreteArray> cont_lam_ub_; - //! container for lagr. mult. general-constraint lower - ct::core::DiscreteArray> cont_lam_lg_; - //! container for lagr. mult. general-constraint upper - ct::core::DiscreteArray> cont_lam_ug_; - - ct::core::StateVectorArray hpi_; //! settings from NLOptConSolver NLOptConSettings settings_; - std::vector qp_mem_; + //! ocp qp dimensions + int dim_size_; + void* dim_mem_; + struct d_ocp_qp_dim dim_; + + void* qp_mem_; struct d_ocp_qp qp_; - std::vector qp_sol_mem_; + void* qp_sol_mem_; struct d_ocp_qp_sol qp_sol_; - struct d_ipm_hard_ocp_qp_arg arg_; //! IPM settings - std::vector ipm_mem_; - struct d_ipm_hard_ocp_qp_workspace workspace_; + void* ipm_arg_mem_; + struct d_ocp_qp_ipm_arg arg_; + + // workspace + void* ipm_mem_; + struct d_ocp_qp_ipm_ws workspace_; + int hpipm_status_; // status code after solving + + // todo make this a setting + ::hpipm_mode mode_ = ::hpipm_mode::SPEED; // ROBUST/BALANCED; see also hpipm_common.h }; diff --git a/ct_optcon/include/ct/optcon/solver/lqp/LQOCSolver.hpp b/ct_optcon/include/ct/optcon/solver/lqp/LQOCSolver.hpp index 733c291fa..2018fb91c 100644 --- a/ct_optcon/include/ct/optcon/solver/lqp/LQOCSolver.hpp +++ b/ct_optcon/include/ct/optcon/solver/lqp/LQOCSolver.hpp @@ -31,8 +31,9 @@ class LQOCSolver * @param lqocProblem shared_ptr to the LQOCProblem to be solved. */ LQOCSolver(const std::shared_ptr& lqocProblem = nullptr) : lqocProblem_(lqocProblem) {} - //! destructor - virtual ~LQOCSolver() {} + + virtual ~LQOCSolver() = default; + /*! * set a new problem * update the shared_ptr to the LQOCProblem instance and call initialize instance deriving from this class. @@ -44,13 +45,17 @@ class LQOCSolver lqocProblem_ = lqocProblem; } - virtual void configure(const NLOptConSettings& settings) = 0; //! setup and configure the box constraints - virtual void configureBoxConstraints(std::shared_ptr> lqocProblem) + virtual void configureInputBoxConstraints(std::shared_ptr> lqocProblem) + { + throw std::runtime_error("input box constraints are not available for this solver."); + } + + virtual void configureStateBoxConstraints(std::shared_ptr> lqocProblem) { - throw std::runtime_error("box constraints are not available for this solver."); + throw std::runtime_error("state box constraints are not available for this solver."); } //! setup and configure the general (in)equality constraints @@ -64,22 +69,35 @@ class LQOCSolver //! solve the LQOC problem virtual void solve() = 0; - //! extract the solution (can be overriden if additional extraction steps required in specific solver) - virtual void extractLQSolution(){}; virtual void solveSingleStage(int N) { throw std::runtime_error("solveSingleStage not available for this solver."); } + //! extract the solution (can be overriden if additional extraction steps required in specific solver) + virtual void computeStatesAndControls() = 0; + //! return solution for state + const ct::core::StateVectorArray& getSolutionState() { return x_sol_; } + //! return solution for control + const ct::core::ControlVectorArray& getSolutionControl() { return u_sol_; } + + //! return TVLQR feedback matrices + virtual void computeFeedbackMatrices() = 0; + const ct::core::FeedbackArray& getSolutionFeedback() { return L_; } + + //! compute iLQR-style lv + virtual void compute_lv() = 0; + //! return iLQR-style feedforward lv + virtual const ct::core::ControlVectorArray& get_lv() { return lv_; } + + //! return the smallest eigenvalue virtual SCALAR getSmallestEigenvalue() { throw std::runtime_error("getSmallestEigenvalue not available for this solver."); } - const ct::core::StateVectorArray& getSolutionState() { return x_sol_; } - const ct::core::ControlVectorArray& getSolutionControl() { return u_sol_; } - const ct::core::FeedbackArray& getSolutionFeedback() { return L_; } + protected: virtual void setProblemImpl(std::shared_ptr lqocProblem) = 0; @@ -88,6 +106,8 @@ class LQOCSolver core::StateVectorArray x_sol_; // solution in x core::ControlVectorArray u_sol_; // solution in u ct::core::FeedbackArray L_; // solution feedback + ct::core::ControlVectorArray lv_; // feedforward increment (iLQR-style) }; + } // namespace optcon } // namespace ct diff --git a/ct_optcon/package.xml b/ct_optcon/package.xml index 77bd296a0..e58867a36 100644 --- a/ct_optcon/package.xml +++ b/ct_optcon/package.xml @@ -1,6 +1,6 @@ ct_optcon - 3.0.1 + 3.0.2 Control toolbox - optcon module. diff --git a/ct_optcon/prespec/nloc/algorithms/GNMS.cpp.in b/ct_optcon/prespec/nloc/algorithms/GNMS.cpp.in new file mode 100644 index 000000000..6ee3d8b53 --- /dev/null +++ b/ct_optcon/prespec/nloc/algorithms/GNMS.cpp.in @@ -0,0 +1,6 @@ +#include +#include + +#if @POS_DIM_PRESPEC@ && @VEL_DIM_PRESPEC@ && @DOUBLE_OR_FLOAT@ +template class ct::optcon::MultipleShooting<@STATE_DIM_PRESPEC@, @CONTROL_DIM_PRESPEC@, @POS_DIM_PRESPEC@, @VEL_DIM_PRESPEC@, @SCALAR_PRESPEC@>; +#endif \ No newline at end of file diff --git a/ct_optcon/prespec/nloc/algorithms/gnms/GNMS.cpp.in b/ct_optcon/prespec/nloc/algorithms/gnms/GNMS.cpp.in deleted file mode 100644 index 4728613ff..000000000 --- a/ct_optcon/prespec/nloc/algorithms/gnms/GNMS.cpp.in +++ /dev/null @@ -1,6 +0,0 @@ -#include -#include - -#if @POS_DIM_PRESPEC@ && @VEL_DIM_PRESPEC@ && @DOUBLE_OR_FLOAT@ -template class ct::optcon::GNMS<@STATE_DIM_PRESPEC@, @CONTROL_DIM_PRESPEC@, @POS_DIM_PRESPEC@, @VEL_DIM_PRESPEC@, @SCALAR_PRESPEC@>; -#endif \ No newline at end of file diff --git a/ct_optcon/prespec/nloc/algorithms/iLQR.cpp.in b/ct_optcon/prespec/nloc/algorithms/iLQR.cpp.in new file mode 100644 index 000000000..4f769125f --- /dev/null +++ b/ct_optcon/prespec/nloc/algorithms/iLQR.cpp.in @@ -0,0 +1,6 @@ +#include +#include + +#if @POS_DIM_PRESPEC@ && @VEL_DIM_PRESPEC@ && @DOUBLE_OR_FLOAT@ +template class ct::optcon::SingleShooting<@STATE_DIM_PRESPEC@, @CONTROL_DIM_PRESPEC@, @POS_DIM_PRESPEC@, @VEL_DIM_PRESPEC@, @SCALAR_PRESPEC@>; +#endif \ No newline at end of file diff --git a/ct_optcon/prespec/nloc/algorithms/ilqr/iLQR.cpp.in b/ct_optcon/prespec/nloc/algorithms/ilqr/iLQR.cpp.in deleted file mode 100644 index 009b9e310..000000000 --- a/ct_optcon/prespec/nloc/algorithms/ilqr/iLQR.cpp.in +++ /dev/null @@ -1,6 +0,0 @@ -#include -#include - -#if @POS_DIM_PRESPEC@ && @VEL_DIM_PRESPEC@ && @DOUBLE_OR_FLOAT@ -template class ct::optcon::iLQR<@STATE_DIM_PRESPEC@, @CONTROL_DIM_PRESPEC@, @POS_DIM_PRESPEC@, @VEL_DIM_PRESPEC@, @SCALAR_PRESPEC@>; -#endif \ No newline at end of file diff --git a/ct_optcon/test/CMakeLists.txt b/ct_optcon/test/CMakeLists.txt index b864b8754..07aa5de2f 100644 --- a/ct_optcon/test/CMakeLists.txt +++ b/ct_optcon/test/CMakeLists.txt @@ -38,26 +38,32 @@ package_add_test(LinearSystemTest nloc/LinearSystemTest.cpp) package_add_test(NonlinearSystemTest nloc/nonlinear/NonlinearSystemTest.cpp) package_add_test(NLOC_MPCTest mpc/NLOC_MPCTest.cpp) #package_add_test(SymplecticTest nloc/SymplecticTest.cpp) # make proper test -package_add_test(constraint_comparison constraint/ConstraintComparison.cpp) -package_add_test(constraint_test constraint/ConstraintTest.cpp) package_add_test(SparseBoxConstraintTest constraint/SparseBoxConstraintTest.cpp) - -package_add_test(CostFunctionTests costfunction/CostFunctionTests.cpp) -package_add_test(LoadFromFileTest costfunction/LoadFromFileTest.cpp) +if(CPPADCG) + message(STATUS "ct_optcon: building unit tests requiring CPPADCG") + package_add_test(constraint_comparison constraint/ConstraintComparison.cpp) + package_add_test(constraint_test constraint/ConstraintTest.cpp) + package_add_test(CostFunctionTests costfunction/CostFunctionTests.cpp) + package_add_test(LoadFromFileTest costfunction/LoadFromFileTest.cpp) +endif() package_add_test(dms_test dms/oscillator/oscDMSTest.cpp) package_add_test(dms_test_all_var dms/oscillator/oscDMSTestAllVariants.cpp) package_add_test(system_interface_test system_interface/SystemInterfaceTest.cpp) if(HPIPM) + message(STATUS "ct_optcon: building unit tests requiring HPIPM") ## some legacy executables (TODO: make example or make test) add_executable(LQOCSolverTiming solver/linear/LQOCSolverTiming.cpp) target_link_libraries(LQOCSolverTiming ct_optcon) package_add_test(LQOCSolverTest solver/linear/LQOCSolverTest.cpp) package_add_test(ConstrainedLQOCSolverTest solver/linear/ConstrainedLQOCSolverTest.cpp) - package_add_test(ConstrainedNLOCTest nloc/constrained/ConstrainedNLOCTest.cpp) package_add_test(LinearSystemSolverComparison nloc/LinearSystemSolverComparison.cpp) + if(CPPADCG) + message(STATUS "ct_optcon: building unit tests requiring CPPADCG and HPIPM") + package_add_test(ConstrainedNLOCTest nloc/constrained/ConstrainedNLOCTest.cpp) + endif() endif() diff --git a/ct_optcon/test/constraint/ConstraintTest.h b/ct_optcon/test/constraint/ConstraintTest.h index 3a5de76d0..8c71909ea 100644 --- a/ct_optcon/test/constraint/ConstraintTest.h +++ b/ct_optcon/test/constraint/ConstraintTest.h @@ -69,6 +69,7 @@ class PureStateConstraint_Example : public ct::optcon::ConstraintBase& A) { A_ = A; } + private: Eigen::Matrix A_; }; @@ -110,7 +111,10 @@ class StateInputConstraint_Example : public ct::optcon::ConstraintBase evaluateCppadCg( const core::StateVector& x, const core::ControlVector& u, diff --git a/ct_optcon/test/mpc/NLOC_MPCTest.h b/ct_optcon/test/mpc/NLOC_MPCTest.h index ce3750937..d142205c1 100644 --- a/ct_optcon/test/mpc/NLOC_MPCTest.h +++ b/ct_optcon/test/mpc/NLOC_MPCTest.h @@ -61,7 +61,6 @@ TEST(MPCTestA, ForwardIntegratorTest) nloc_settings.discretization = NLOptConSettings::APPROXIMATION::FORWARD_EULER; nloc_settings.nlocp_algorithm = NLOptConSettings::NLOCP_ALGORITHM::ILQR; nloc_settings.lqocp_solver = NLOptConSettings::LQOCP_SOLVER::GNRICCATI_SOLVER; - nloc_settings.closedLoopShooting = true; nloc_settings.printSummary = false; // number of steps @@ -195,9 +194,8 @@ TEST(MPCTestB, NLOC_MPC_DoublePrecision) nloc_settings.min_cost_improvement = 1e-10; // strict bounds to reach a solution very close to optimality nloc_settings.discretization = NLOptConSettings::APPROXIMATION::FORWARD_EULER; nloc_settings.lqocp_solver = NLOptConSettings::LQOCP_SOLVER::GNRICCATI_SOLVER; - nloc_settings.closedLoopShooting = true; nloc_settings.integrator = ct::core::IntegrationType::EULER; - nloc_settings.lineSearchSettings.active = false; + nloc_settings.lineSearchSettings.type = LineSearchSettings::TYPE::SIMPLE; nloc_settings.nThreads = 1; nloc_settings.nThreadsEigen = 1; nloc_settings.printSummary = false; diff --git a/ct_optcon/test/nloc/LinearSystemSolverComparison.h b/ct_optcon/test/nloc/LinearSystemSolverComparison.h index 590587c77..963d4c9c2 100644 --- a/ct_optcon/test/nloc/LinearSystemSolverComparison.h +++ b/ct_optcon/test/nloc/LinearSystemSolverComparison.h @@ -55,133 +55,125 @@ TEST(LinearSystemsSolverComparison, LinearSystemsSolverComparison) { nloc_settings.nlocp_algorithm = static_cast(algClass); - // change between closed-loop and open-loop - for (int toggleClosedLoop = 0; toggleClosedLoop <= 1; toggleClosedLoop++) + // switch line search on or off + for (int toggleLS = 0; toggleLS <= 1; toggleLS++) { - nloc_settings.closedLoopShooting = (bool)toggleClosedLoop; + nloc_settings.lineSearchSettings.type = static_cast(toggleLS); - // switch line search on or off - for (int toggleLS = 0; toggleLS <= 1; toggleLS++) + // toggle between single and multi-threading + for (size_t nThreads = 1; nThreads < 5; nThreads = nThreads + 3) { - nloc_settings.lineSearchSettings.active = (bool)toggleLS; + nloc_settings.nThreads = nThreads; - // toggle between single and multi-threading - for (size_t nThreads = 1; nThreads < 5; nThreads = nThreads + 3) + // toggle between iLQR/GNMS and hybrid methods with K_shot !=1 + for (size_t kshot = 1; kshot < 11; kshot = kshot + 9) { - nloc_settings.nThreads = nThreads; + nloc_settings.K_shot = kshot; - // toggle between iLQR/GNMS and hybrid methods with K_shot !=1 - for (size_t kshot = 1; kshot < 11; kshot = kshot + 9) - { - nloc_settings.K_shot = kshot; + if (kshot > 1 && nloc_settings.nlocp_algorithm == NLOptConSettings::NLOCP_ALGORITHM::ILQR) + continue; // proceed to next test case - if (kshot > 1 && nloc_settings.nlocp_algorithm == NLOptConSettings::NLOCP_ALGORITHM::ILQR) - continue; // proceed to next test case + // toggle sensitivity integrator + for (size_t sensInt = 0; sensInt <= 1; sensInt++) + { + nloc_settings.useSensitivityIntegrator = bool(sensInt); - // toggle sensitivity integrator - for (size_t sensInt = 0; sensInt <= 1; sensInt++) + // toggle over simulation time-steps + for (size_t ksim = 1; ksim <= 5; ksim = ksim + 4) { - nloc_settings.useSensitivityIntegrator = bool(sensInt); + nloc_settings.K_sim = ksim; - // toggle over simulation time-steps - for (size_t ksim = 1; ksim <= 5; ksim = ksim + 4) - { - nloc_settings.K_sim = ksim; + // catch special case, simulation sub-time steps only make sense when sensitivity integrator active + if ((nloc_settings.useSensitivityIntegrator == false) && (ksim > 1)) + continue; // proceed to next test case - // catch special case, simulation sub-time steps only make sense when sensitivity integrator active - if ((nloc_settings.useSensitivityIntegrator == false) && (ksim > 1)) + // toggle integrator type + for (size_t integratortype = 0; integratortype <= 1; integratortype++) + { + if (integratortype == 0) + nloc_settings.integrator = ct::core::IntegrationType::EULERCT; + else if (integratortype == 1 && nloc_settings.useSensitivityIntegrator == true) + { + // use RK4 with exactly integrated sensitivities + nloc_settings.integrator = ct::core::IntegrationType::RK4CT; + } + else continue; // proceed to next test case - // toggle integrator type - for (size_t integratortype = 0; integratortype <= 1; integratortype++) - { - if (integratortype == 0) - nloc_settings.integrator = ct::core::IntegrationType::EULERCT; - else if (integratortype == 1 && nloc_settings.useSensitivityIntegrator == true) - { - // use RK4 with exactly integrated sensitivities - nloc_settings.integrator = ct::core::IntegrationType::RK4CT; - } - else - continue; // proceed to next test case - - shared_ptr> nonlinearSystem( - new LinearOscillator()); - shared_ptr> analyticLinearSystem( - new LinearOscillatorLinear()); - shared_ptr> costFunction = - tpl::createCostFunctionLinearOscillator(x_final); - - // times - ct::core::Time tf = 1.0; - size_t nSteps = nloc_settings.computeK(tf); - - // initial controller - StateVectorArray x0(nSteps + 1, initState); - ControlVector uff; - uff << kStiffness * initState(0); - ControlVectorArray u0(nSteps, uff); - - FeedbackArray u0_fb( - nSteps, FeedbackMatrix::Zero()); - ControlVectorArray u0_ff(nSteps, ControlVector::Zero()); - - NLOptConSolver::Policy_t initController(x0, u0, u0_fb, nloc_settings.dt); - - // construct OptCon Problem - ContinuousOptConProblem optConProblem( - tf, x0[0], nonlinearSystem, costFunction, analyticLinearSystem); - - // NLOC solver employing GNRiccati - nloc_settings.lqocp_solver = NLOptConSettings::LQOCP_SOLVER::GNRICCATI_SOLVER; - NLOptConSolver solver_gnriccati(optConProblem, nloc_settings); - solver_gnriccati.configure(nloc_settings); - solver_gnriccati.setInitialGuess(initController); - //! run two iterations to solve LQ problem - solver_gnriccati.runIteration(); - solver_gnriccati.runIteration(); - - - // NLOC solver employing HPIPM - nloc_settings.lqocp_solver = NLOptConSettings::LQOCP_SOLVER::HPIPM_SOLVER; - NLOptConSolver solver_hpipm(optConProblem, nloc_settings); - solver_hpipm.configure(nloc_settings); - solver_hpipm.setInitialGuess(initController); - //! run two iterations to solve LQ problem - solver_hpipm.runIteration(); - solver_hpipm.runIteration(); - - //! retrieve summaries - const SummaryAllIterations& sumGn = - solver_gnriccati.getBackend()->getSummary(); - const SummaryAllIterations& sumHpipm = - solver_hpipm.getBackend()->getSummary(); - - //! check that all logs from both solvers are identical - // first iteration - ASSERT_NEAR(sumGn.lx_norms.back(), sumHpipm.lx_norms.back(), 1e-6); - ASSERT_NEAR(sumGn.lu_norms.back(), sumHpipm.lu_norms.back(), 1e-6); - ASSERT_NEAR(sumGn.defect_l1_norms.back(), sumHpipm.defect_l1_norms.back(), 1e-6); - ASSERT_NEAR(sumGn.defect_l2_norms.back(), sumHpipm.defect_l2_norms.back(), 1e-6); - ASSERT_NEAR(sumGn.merits.back(), sumHpipm.merits.back(), 1e-6); - - // second iteration - ASSERT_NEAR(sumGn.lx_norms.front(), sumHpipm.lx_norms.front(), 1e-6); - ASSERT_NEAR(sumGn.lu_norms.front(), sumHpipm.lu_norms.front(), 1e-6); - ASSERT_NEAR(sumGn.defect_l1_norms.front(), sumHpipm.defect_l1_norms.front(), 1e-6); - ASSERT_NEAR(sumGn.defect_l2_norms.front(), sumHpipm.defect_l2_norms.front(), 1e-6); - ASSERT_NEAR(sumGn.merits.front(), sumHpipm.merits.front(), 1e-6); - - testCounter++; - - } // toggle integrator type - } // toggle simulation time steps - } // toggle sensitivity integrator - } // toggle k_shot - } // toggle multi-threading / single-threading - } // toggle line-search - } // toggle closed-loop - } // toggle solver class + shared_ptr> nonlinearSystem( + new LinearOscillator()); + shared_ptr> analyticLinearSystem( + new LinearOscillatorLinear()); + shared_ptr> costFunction = + tpl::createCostFunctionLinearOscillator(x_final); + + // times + ct::core::Time tf = 1.0; + size_t nSteps = nloc_settings.computeK(tf); + + // initial controller + StateVectorArray x0(nSteps + 1, initState); + ControlVector uff; + uff << kStiffness * initState(0); + ControlVectorArray u0(nSteps, uff); + + FeedbackArray u0_fb( + nSteps, FeedbackMatrix::Zero()); + ControlVectorArray u0_ff(nSteps, ControlVector::Zero()); + + NLOptConSolver::Policy_t initController(x0, u0, u0_fb, nloc_settings.dt); + + // construct OptCon Problem + ContinuousOptConProblem optConProblem( + tf, x0[0], nonlinearSystem, costFunction, analyticLinearSystem); + + // NLOC solver employing GNRiccati + nloc_settings.lqocp_solver = NLOptConSettings::LQOCP_SOLVER::GNRICCATI_SOLVER; + NLOptConSolver solver_gnriccati(optConProblem, nloc_settings); + solver_gnriccati.configure(nloc_settings); + solver_gnriccati.setInitialGuess(initController); + //! run two iterations to solve LQ problem + solver_gnriccati.runIteration(); + solver_gnriccati.runIteration(); + + + // NLOC solver employing HPIPM + nloc_settings.lqocp_solver = NLOptConSettings::LQOCP_SOLVER::HPIPM_SOLVER; + NLOptConSolver solver_hpipm(optConProblem, nloc_settings); + solver_hpipm.configure(nloc_settings); + solver_hpipm.setInitialGuess(initController); + //! run two iterations to solve LQ problem + solver_hpipm.runIteration(); + solver_hpipm.runIteration(); + + //! retrieve summaries + const SummaryAllIterations& sumGn = solver_gnriccati.getBackend()->getSummary(); + const SummaryAllIterations& sumHpipm = solver_hpipm.getBackend()->getSummary(); + + //! check that all logs from both solvers are identical + // first iteration + ASSERT_NEAR(sumGn.lx_norms.back(), sumHpipm.lx_norms.back(), 1e-6); + ASSERT_NEAR(sumGn.lu_norms.back(), sumHpipm.lu_norms.back(), 1e-6); + ASSERT_NEAR(sumGn.defect_l1_norms.back(), sumHpipm.defect_l1_norms.back(), 1e-6); + ASSERT_NEAR(sumGn.defect_l2_norms.back(), sumHpipm.defect_l2_norms.back(), 1e-6); + ASSERT_NEAR(sumGn.merits.back(), sumHpipm.merits.back(), 1e-6); + + // second iteration + ASSERT_NEAR(sumGn.lx_norms.front(), sumHpipm.lx_norms.front(), 1e-6); + ASSERT_NEAR(sumGn.lu_norms.front(), sumHpipm.lu_norms.front(), 1e-6); + ASSERT_NEAR(sumGn.defect_l1_norms.front(), sumHpipm.defect_l1_norms.front(), 1e-6); + ASSERT_NEAR(sumGn.defect_l2_norms.front(), sumHpipm.defect_l2_norms.front(), 1e-6); + ASSERT_NEAR(sumGn.merits.front(), sumHpipm.merits.front(), 1e-6); + + testCounter++; + + } // toggle integrator type + } // toggle simulation time steps + } // toggle sensitivity integrator + } // toggle k_shot + } // toggle multi-threading / single-threading + } // toggle line-search + } // toggle solver class std::cout << "Performed " << testCounter << " successful NLOC tests with linear systems" << std::endl; diff --git a/ct_optcon/test/nloc/LinearSystemTest.h b/ct_optcon/test/nloc/LinearSystemTest.h index 9ba2f4e35..a69118e6e 100644 --- a/ct_optcon/test/nloc/LinearSystemTest.h +++ b/ct_optcon/test/nloc/LinearSystemTest.h @@ -62,115 +62,109 @@ TEST(LinearSystemsTest, NLOCSolverTest) { nloc_settings.nlocp_algorithm = static_cast(algClass); - // change between closed-loop and open-loop - for (int toggleClosedLoop = 0; toggleClosedLoop <= 1; toggleClosedLoop++) + // switch line search on or off + for (int toggleLS = 0; toggleLS <= 1; toggleLS++) { - nloc_settings.closedLoopShooting = (bool)toggleClosedLoop; + nloc_settings.lineSearchSettings.type = static_cast(toggleLS); - // switch line search on or off - for (int toggleLS = 0; toggleLS <= 1; toggleLS++) + // toggle between single and multi-threading + for (size_t nThreads = 1; nThreads < 5; nThreads = nThreads + 3) { - nloc_settings.lineSearchSettings.active = (bool)toggleLS; + nloc_settings.nThreads = nThreads; - // toggle between single and multi-threading - for (size_t nThreads = 1; nThreads < 5; nThreads = nThreads + 3) + // toggle between iLQR/GNMS and hybrid methods with K_shot !=1 + for (size_t kshot = 1; kshot < 11; kshot = kshot + 9) { - nloc_settings.nThreads = nThreads; + nloc_settings.K_shot = kshot; - // toggle between iLQR/GNMS and hybrid methods with K_shot !=1 - for (size_t kshot = 1; kshot < 11; kshot = kshot + 9) - { - nloc_settings.K_shot = kshot; + if (kshot > 1 && nloc_settings.nlocp_algorithm == NLOptConSettings::NLOCP_ALGORITHM::ILQR) + continue; // proceed to next test case - if (kshot > 1 && nloc_settings.nlocp_algorithm == NLOptConSettings::NLOCP_ALGORITHM::ILQR) - continue; // proceed to next test case + // toggle sensitivity integrator + for (size_t sensInt = 0; sensInt <= 1; sensInt++) + { + nloc_settings.useSensitivityIntegrator = bool(sensInt); - // toggle sensitivity integrator - for (size_t sensInt = 0; sensInt <= 1; sensInt++) + // toggle over simulation time-steps + for (size_t ksim = 1; ksim <= 5; ksim = ksim + 4) { - nloc_settings.useSensitivityIntegrator = bool(sensInt); + nloc_settings.K_sim = ksim; - // toggle over simulation time-steps - for (size_t ksim = 1; ksim <= 5; ksim = ksim + 4) - { - nloc_settings.K_sim = ksim; + // catch special case, simulation sub-time steps only make sense when sensitivity integrator active + if ((nloc_settings.useSensitivityIntegrator == false) && (ksim > 1)) + continue; // proceed to next test case - // catch special case, simulation sub-time steps only make sense when sensitivity integrator active - if ((nloc_settings.useSensitivityIntegrator == false) && (ksim > 1)) + // toggle integrator type + for (size_t integratortype = 0; integratortype <= 1; integratortype++) + { + if (integratortype == 0) + nloc_settings.integrator = ct::core::IntegrationType::EULERCT; + else if (integratortype == 1 && nloc_settings.useSensitivityIntegrator == true) + { + // use RK4 with exactly integrated sensitivities + nloc_settings.integrator = ct::core::IntegrationType::RK4CT; + } + else continue; // proceed to next test case - // toggle integrator type - for (size_t integratortype = 0; integratortype <= 1; integratortype++) - { - if (integratortype == 0) - nloc_settings.integrator = ct::core::IntegrationType::EULERCT; - else if (integratortype == 1 && nloc_settings.useSensitivityIntegrator == true) - { - // use RK4 with exactly integrated sensitivities - nloc_settings.integrator = ct::core::IntegrationType::RK4CT; - } - else - continue; // proceed to next test case - - // nloc_settings.print(); - - shared_ptr> nonlinearSystem( - new LinearOscillator()); - shared_ptr> analyticLinearSystem( - new LinearOscillatorLinear()); - shared_ptr> costFunction = - tpl::createCostFunctionLinearOscillator(x_final); - - // times - ct::core::Time tf = 1.0; - size_t nSteps = nloc_settings.computeK(tf); - - // initial controller - StateVectorArray x0(nSteps + 1, initState); - ControlVector uff; - uff << kStiffness * initState(0); - ControlVectorArray u0(nSteps, uff); - - FeedbackArray u0_fb( - nSteps, FeedbackMatrix::Zero()); - ControlVectorArray u0_ff(nSteps, ControlVector::Zero()); - - NLOptConSolver::Policy_t initController(x0, u0, u0_fb, nloc_settings.dt); - - // construct single-core single subsystem OptCon Problem - ContinuousOptConProblem optConProblem( - tf, x0[0], nonlinearSystem, costFunction, analyticLinearSystem); - - - NLOptConSolver solver(optConProblem, nloc_settings); - solver.configure(nloc_settings); - solver.setInitialGuess(initController); - - //! run two iterations to solve LQ problem - solver.runIteration(); // only this one should be required to solve LQ problem - solver.runIteration(); - //! retrieve summary of the optimization - const SummaryAllIterations& summary = solver.getBackend()->getSummary(); - //! check that the policy improved in the first iteration - ASSERT_GT(summary.lx_norms.front(), 1e-9); - ASSERT_GT(summary.lu_norms.front(), 1e-9); - - //! check that we are converged after the first iteration - ASSERT_LT(summary.lx_norms.back(), 1e-10); - ASSERT_LT(summary.lu_norms.back(), 1e-10); - ASSERT_LT(summary.defect_l1_norms.back(), 1e-10); - ASSERT_LT(summary.defect_l2_norms.back(), 1e-10); - - testCounter++; - - } // toggle integrator type - } // toggle simulation time steps - } // toggle sensitivity integrator - } // toggle k_shot - } // toggle multi-threading / single-threading - } // toggle line-search - } // toggle closed-loop - } // toggle solver class + // nloc_settings.print(); + + shared_ptr> nonlinearSystem( + new LinearOscillator()); + shared_ptr> analyticLinearSystem( + new LinearOscillatorLinear()); + shared_ptr> costFunction = + tpl::createCostFunctionLinearOscillator(x_final); + + // times + ct::core::Time tf = 1.0; + size_t nSteps = nloc_settings.computeK(tf); + + // initial controller + StateVectorArray x0(nSteps + 1, initState); + ControlVector uff; + uff << kStiffness * initState(0); + ControlVectorArray u0(nSteps, uff); + + FeedbackArray u0_fb( + nSteps, FeedbackMatrix::Zero()); + ControlVectorArray u0_ff(nSteps, ControlVector::Zero()); + + NLOptConSolver::Policy_t initController(x0, u0, u0_fb, nloc_settings.dt); + + // construct single-core single subsystem OptCon Problem + ContinuousOptConProblem optConProblem( + tf, x0[0], nonlinearSystem, costFunction, analyticLinearSystem); + + + NLOptConSolver solver(optConProblem, nloc_settings); + solver.configure(nloc_settings); + solver.setInitialGuess(initController); + + //! run two iterations to solve LQ problem + solver.runIteration(); // only this one should be required to solve LQ problem + solver.runIteration(); + //! retrieve summary of the optimization + const SummaryAllIterations& summary = solver.getBackend()->getSummary(); + //! check that the policy improved in the first iteration + ASSERT_GT(summary.lx_norms.front(), 1e-9); + ASSERT_GT(summary.lu_norms.front(), 1e-9); + + //! check that we are converged after the first iteration + ASSERT_LT(summary.lx_norms.back(), 1e-10); + ASSERT_LT(summary.lu_norms.back(), 1e-10); + ASSERT_LT(summary.defect_l1_norms.back(), 1e-10); + ASSERT_LT(summary.defect_l2_norms.back(), 1e-10); + + testCounter++; + + } // toggle integrator type + } // toggle simulation time steps + } // toggle sensitivity integrator + } // toggle k_shot + } // toggle multi-threading / single-threading + } // toggle line-search + } // toggle solver class std::cout << "Performed " << testCounter << " successful NLOC tests with linear systems" << std::endl; diff --git a/ct_optcon/test/nloc/SymplecticTest.h b/ct_optcon/test/nloc/SymplecticTest.h index 56f7bd072..045869701 100644 --- a/ct_optcon/test/nloc/SymplecticTest.h +++ b/ct_optcon/test/nloc/SymplecticTest.h @@ -131,14 +131,12 @@ void symplecticTest() gnms_settings.useSensitivityIntegrator = true; gnms_settings.nlocp_algorithm = NLOptConSettings::NLOCP_ALGORITHM::GNMS; gnms_settings.lqocp_solver = NLOptConSettings::LQOCP_SOLVER::GNRICCATI_SOLVER; - gnms_settings.closedLoopShooting = false; - gnms_settings.lineSearchSettings.active = false; + gnms_settings.lineSearchSettings.type = LineSearchSettings::TYPE::NONE; gnms_settings.loggingPrefix = "GNMS"; gnms_settings.printSummary = false; NLOptConSettings ilqr_settings = gnms_settings; - ilqr_settings.closedLoopShooting = true; ilqr_settings.nlocp_algorithm = NLOptConSettings::NLOCP_ALGORITHM::ILQR; ilqr_settings.loggingPrefix = "ILQR"; diff --git a/ct_optcon/test/nloc/constrained/ConstrainedNLOCTest.cpp b/ct_optcon/test/nloc/constrained/ConstrainedNLOCTest.cpp index 485df4ca9..d51c5a072 100644 --- a/ct_optcon/test/nloc/constrained/ConstrainedNLOCTest.cpp +++ b/ct_optcon/test/nloc/constrained/ConstrainedNLOCTest.cpp @@ -144,7 +144,7 @@ NLOptConSolver generateSolver(ContinuousOptConProbleminitialize(); auto optConProblem_box = generateUnconstrainedOCP(); - optConProblem_box.setBoxConstraints(boxConstraints); + optConProblem_box.setInputBoxConstraints(boxConstraints); // OPTION 2 - create constraint container for "general" constraints, same constraint objective @@ -262,7 +262,7 @@ TEST(Constrained_NLOC_Test, comparePureStateConstraints) boxConstraints->initialize(); auto optConProblem_box = generateUnconstrainedOCP(); - optConProblem_box.setBoxConstraints(boxConstraints); + optConProblem_box.setStateBoxConstraints(boxConstraints); // OPTION 2 - create constraint container for "general" constraints, same constraint objective @@ -296,74 +296,6 @@ TEST(Constrained_NLOC_Test, comparePureStateConstraints) } -/* - * This test makes sure NLOC throws an exception in case the ordering of the box constraints is wrong. - */ -/* -TEST(Constrained_NLOC_Test, checkBoxConstraintOrdering) -{ - // create constraint container for box constraints - std::shared_ptr> boxConstraints_order1( - new ct::optcon::ConstraintContainerAnalytical()); - std::shared_ptr> boxConstraints_order2( - new ct::optcon::ConstraintContainerAnalytical()); - - // create a box constraint on the state vector - Eigen::VectorXi sp_state(state_dim); - sp_state << 0, 1; - Eigen::VectorXd x_lb(1); - Eigen::VectorXd x_ub(1); - x_lb.setConstant(-0.2); - x_ub = -x_lb; - std::shared_ptr> stateConstraint( - new StateConstraint(x_lb, x_ub, sp_state)); - stateConstraint->setName("StateConstraint"); - - - // create a box constraint on the control input - Eigen::VectorXi sp_control(control_dim); - sp_control << 1; - Eigen::VectorXd u_lb(control_dim); - Eigen::VectorXd u_ub(control_dim); - u_lb.setConstant(-0.5); - u_ub = -u_lb; - std::shared_ptr> controlConstraint( - new ControlInputConstraint(u_lb, u_ub, sp_control)); - controlConstraint->setName("ControlInputConstraint"); - - // put in state constraints before box constraints - boxConstraints_order1->addIntermediateConstraint(stateConstraint, verbose); - boxConstraints_order1->addIntermediateConstraint(controlConstraint, verbose); - boxConstraints_order1->initialize(); - - // put in control constraints before state constraints - boxConstraints_order2->addIntermediateConstraint(controlConstraint, verbose); - boxConstraints_order2->addIntermediateConstraint(stateConstraint, verbose); - boxConstraints_order2->initialize(); - - auto optConProblem_order1 = generateUnconstrainedOCP(); - auto optConProblem_order2 = generateUnconstrainedOCP(); - - optConProblem_order1.setBoxConstraints(boxConstraints_order1); - optConProblem_order2.setBoxConstraints(boxConstraints_order2); - - - // create solvers and solve - auto nloc_order1 = generateSolver(optConProblem_order1); - auto nloc_order2 = generateSolver(optConProblem_order2); - - try - { - nloc_order1.solve(); // ... this should throw an exception, because of wrong box constraint ordering. - FAIL(); - } catch (std::runtime_error& e) - { - } - - ASSERT_NO_THROW(nloc_order2.solve()); // this should pass, has correct box constraint ordering. -} -*/ - int main(int argc, char** argv) { testing::InitGoogleTest(&argc, argv); diff --git a/ct_optcon/test/nloc/nonlinear/NonlinearSystemTest.h b/ct_optcon/test/nloc/nonlinear/NonlinearSystemTest.h index 369333a4b..a0f1f463d 100644 --- a/ct_optcon/test/nloc/nonlinear/NonlinearSystemTest.h +++ b/ct_optcon/test/nloc/nonlinear/NonlinearSystemTest.h @@ -116,6 +116,6 @@ TEST(NLOCTest, NonlinearSystemAlgorithmComparison) ASSERT_NEAR(uRollout_gnms[i](0), uRollout_ilqr[i](0), 1e-4); } } -} -} -} +} // namespace example +} // namespace optcon +} // namespace ct diff --git a/ct_optcon/test/nloc/nonlinear/iLQRTest.cpp b/ct_optcon/test/nloc/nonlinear/iLQRTest.cpp index b80ad8c24..7262834e3 100644 --- a/ct_optcon/test/nloc/nonlinear/iLQRTest.cpp +++ b/ct_optcon/test/nloc/nonlinear/iLQRTest.cpp @@ -40,7 +40,6 @@ TEST(ILQRTestA, InstancesComparison) ilqr_settings.discretization = NLOptConSettings::APPROXIMATION::FORWARD_EULER; ilqr_settings.nlocp_algorithm = NLOptConSettings::NLOCP_ALGORITHM::ILQR; ilqr_settings.lqocp_solver = NLOptConSettings::LQOCP_SOLVER::GNRICCATI_SOLVER; - ilqr_settings.closedLoopShooting = true; ilqr_settings.integrator = ct::core::IntegrationType::EULER; ilqr_settings.printSummary = false; ilqr_settings.debugPrint = false; @@ -107,14 +106,14 @@ TEST(ILQRTestA, InstancesComparison) if (i == 0) { std::cout << "Turning Line-Search off" << std::endl; - ilqr_settings.lineSearchSettings.active = false; - ilqr_settings_mp.lineSearchSettings.active = false; + ilqr_settings.lineSearchSettings.type = LineSearchSettings::TYPE::NONE; + ilqr_settings_mp.lineSearchSettings.type = LineSearchSettings::TYPE::NONE; } else { std::cout << "Turning Line-Search on" << std::endl; - ilqr_settings.lineSearchSettings.active = true; - ilqr_settings_mp.lineSearchSettings.active = true; + ilqr_settings.lineSearchSettings.type = LineSearchSettings::TYPE::SIMPLE; + ilqr_settings_mp.lineSearchSettings.type = LineSearchSettings::TYPE::SIMPLE; } ilqr.configure(ilqr_settings); @@ -198,7 +197,6 @@ TEST(ILQRTestB, MultiThreadingTest) ilqr_settings.discretization = NLOptConSettings::APPROXIMATION::FORWARD_EULER; ilqr_settings.nlocp_algorithm = NLOptConSettings::NLOCP_ALGORITHM::ILQR; ilqr_settings.lqocp_solver = NLOptConSettings::LQOCP_SOLVER::GNRICCATI_SOLVER; - ilqr_settings.closedLoopShooting = true; ilqr_settings.integrator = ct::core::IntegrationType::RK4; ilqr_settings.printSummary = false; @@ -249,13 +247,13 @@ TEST(ILQRTestB, MultiThreadingTest) { if (i == 0) { - ilqr_settings.lineSearchSettings.active = false; - ilqr_settings_mp.lineSearchSettings.active = false; + ilqr_settings.lineSearchSettings.type = LineSearchSettings::TYPE::NONE; + ilqr_settings_mp.lineSearchSettings.type = LineSearchSettings::TYPE::NONE; } else { - ilqr_settings.lineSearchSettings.active = true; - ilqr_settings_mp.lineSearchSettings.active = true; + ilqr_settings.lineSearchSettings.type = LineSearchSettings::TYPE::SIMPLE; + ilqr_settings_mp.lineSearchSettings.type = LineSearchSettings::TYPE::SIMPLE; } if (i < 2) @@ -408,7 +406,6 @@ TEST(ILQRTestC, PolicyComparison) ilqr_settings.nlocp_algorithm = NLOptConSettings::NLOCP_ALGORITHM::ILQR; ilqr_settings.lqocp_solver = NLOptConSettings::LQOCP_SOLVER::GNRICCATI_SOLVER; ilqr_settings.integrator = ct::core::IntegrationType::EULER; - ilqr_settings.closedLoopShooting = true; ilqr_settings.fixedHessianCorrection = false; ilqr_settings.printSummary = false; @@ -459,13 +456,13 @@ TEST(ILQRTestC, PolicyComparison) { if (i == 0) { - ilqr_settings.lineSearchSettings.active = false; - ilqr_settings_mp.lineSearchSettings.active = false; + ilqr_settings.lineSearchSettings.type = LineSearchSettings::TYPE::NONE; + ilqr_settings_mp.lineSearchSettings.type = LineSearchSettings::TYPE::NONE; } else { - ilqr_settings.lineSearchSettings.active = true; - ilqr_settings_mp.lineSearchSettings.active = true; + ilqr_settings.lineSearchSettings.type = LineSearchSettings::TYPE::SIMPLE; + ilqr_settings_mp.lineSearchSettings.type = LineSearchSettings::TYPE::SIMPLE; } ilqr.configure(ilqr_settings); diff --git a/ct_optcon/test/nloc/nonlinear/solver.info b/ct_optcon/test/nloc/nonlinear/solver.info index f80f8cd2b..be796d1c3 100644 --- a/ct_optcon/test/nloc/nonlinear/solver.info +++ b/ct_optcon/test/nloc/nonlinear/solver.info @@ -1,11 +1,11 @@ timeHorizon 3.0 -gnms +ilqr { + nlocp_algorithm ILQR integrator EulerCT useSensitivityIntegrator true discretization Forward_euler - closedLoopShooting 1 ; (1 = closed loop shooting, 0 = open-loop shooting) dt 0.01 K_shot 1 K_sim 10 @@ -19,14 +19,13 @@ gnms nThreads 1 nThreadsEigen 1 locp_solver GNRICCATI_SOLVER - nlocp_algorithm ILQR debugPrint false printSummary false loggingPrefix ILQR line_search { - active false ; + type NONE adaptive false ; maxIterations 10 ; alpha_0 1.0 ; @@ -36,12 +35,12 @@ gnms } -ilqr +gnms { + nlocp_algorithm GNMS integrator EulerCT useSensitivityIntegrator true discretization Forward_euler - closedLoopShooting 1 ; (1 = closed loop shooting, 0 = open-loop shooting) dt 0.01 K_shot 60 K_sim 10 @@ -54,7 +53,6 @@ ilqr nThreads 1 nThreadsEigen 1 locp_solver GNRICCATI_SOLVER - nlocp_algorithm GNMS debugPrint false printSummary false loggingPrefix ILQR_GNMS_5 diff --git a/ct_optcon/test/solver/linear/ConstrainedLQOCSolverTest.h b/ct_optcon/test/solver/linear/ConstrainedLQOCSolverTest.h index cda614662..9dff5b4cc 100644 --- a/ct_optcon/test/solver/linear/ConstrainedLQOCSolverTest.h +++ b/ct_optcon/test/solver/linear/ConstrainedLQOCSolverTest.h @@ -58,8 +58,8 @@ void assertStateBounds(const ct::core::StateVectorArray& x, { for (int n = 0; n < sparsity.rows(); n++) { - ASSERT_GE(x[j](sparsity(n) - control_dim), x_lb(n)); - ASSERT_LE(x[j](sparsity(n) - control_dim), x_ub(n)); + ASSERT_GE(x[j](sparsity(n)), x_lb(n)); + ASSERT_LE(x[j](sparsity(n)), x_ub(n)); } } } @@ -75,8 +75,7 @@ void boxConstraintsTest(ct::core::ControlVector u0, int nb_x, Eigen::VectorXd x_lb, Eigen::VectorXd x_ub, - Eigen::VectorXi x_box_sparsity, - Eigen::VectorXi x_box_sparsity_terminal) + Eigen::VectorXi x_box_sparsity) { const size_t N = 5; const double dt = 0.5; @@ -115,6 +114,9 @@ void boxConstraintsTest(ct::core::ControlVector u0, new CostFunctionQuadraticSimple(Q, R, xf, u0, xf, Q)); // solution variables needed later + ct::core::StateVectorArray x_nom(N, x0); + ct::core::ControlVectorArray u_nom(N - 1, u0); + ct::core::StateVectorArray xSol_hpipm; ct::core::ControlVectorArray uSol_hpipm; ct::core::FeedbackArray KSol_hpipm; @@ -127,22 +129,35 @@ void boxConstraintsTest(ct::core::ControlVector u0, } // initialize the optimal control problems for both solvers - lqocProblem1->setFromTimeInvariantLinearQuadraticProblem(x0, u0, discreteExampleSystem, *costFunction, xf, dt); - lqocProblem2->setFromTimeInvariantLinearQuadraticProblem(x0, u0, discreteExampleSystem, *costFunction, xf, dt); + lqocProblem1->setFromTimeInvariantLinearQuadraticProblem(discreteExampleSystem, *costFunction, x0, dt); + lqocProblem2->setFromTimeInvariantLinearQuadraticProblem(discreteExampleSystem, *costFunction, x0, dt); - lqocProblem1->setIntermediateBoxConstraints(nb_u, u_lb, u_ub, u_box_sparsity); - lqocProblem2->setIntermediateBoxConstraints(nb_u, u_lb, u_ub, u_box_sparsity); + lqocProblem1->setInputBoxConstraints(nb_u, u_lb, u_ub, u_box_sparsity, u_nom); + lqocProblem2->setInputBoxConstraints(nb_u, u_lb, u_ub, u_box_sparsity, u_nom); // check that constraint configuration is right ASSERT_TRUE(lqocProblem1->isConstrained()); ASSERT_FALSE(lqocProblem1->isGeneralConstrained()); - ASSERT_TRUE(lqocProblem1->isBoxConstrained()); + ASSERT_TRUE(lqocProblem1->isInputBoxConstrained()); + ASSERT_FALSE(lqocProblem1->isStateBoxConstrained()); // set and try to solve the problem for both solvers - hpipmSolver->configureBoxConstraints(lqocProblem1); + hpipmSolver->configureInputBoxConstraints(lqocProblem1); hpipmSolver->setProblem(lqocProblem1); hpipmSolver->initializeAndAllocate(); hpipmSolver->solve(); + hpipmSolver->computeStatesAndControls(); + hpipmSolver->computeFeedbackMatrices(); + + try + { + hpipmSolver->compute_lv(); + ASSERT_TRUE(false); // should never reach to this point + } catch (std::exception& e) + { + std::cout << "HPIPMSolver failed with exception " << e.what() << std::endl; + ASSERT_TRUE(true); + } try { @@ -178,24 +193,37 @@ void boxConstraintsTest(ct::core::ControlVector u0, // initialize the optimal control problems for both solvers lqocProblem1->setZero(); lqocProblem2->setZero(); - lqocProblem1->setFromTimeInvariantLinearQuadraticProblem(x0, u0, discreteExampleSystem, *costFunction, xf, dt); - lqocProblem2->setFromTimeInvariantLinearQuadraticProblem(x0, u0, discreteExampleSystem, *costFunction, xf, dt); + lqocProblem1->setFromTimeInvariantLinearQuadraticProblem(discreteExampleSystem, *costFunction, x0, dt); + lqocProblem2->setFromTimeInvariantLinearQuadraticProblem(discreteExampleSystem, *costFunction, x0, dt); - lqocProblem1->setIntermediateBoxConstraints(nb_x, x_lb, x_ub, x_box_sparsity); - lqocProblem2->setIntermediateBoxConstraints(nb_x, x_lb, x_ub, x_box_sparsity); - lqocProblem1->setTerminalBoxConstraints(nb_x, x_lb, x_ub, x_box_sparsity_terminal); - lqocProblem2->setTerminalBoxConstraints(nb_x, x_lb, x_ub, x_box_sparsity_terminal); + lqocProblem1->setIntermediateStateBoxConstraints(nb_x, x_lb, x_ub, x_box_sparsity, x_nom); + lqocProblem2->setIntermediateStateBoxConstraints(nb_x, x_lb, x_ub, x_box_sparsity, x_nom); + lqocProblem1->setTerminalBoxConstraints(nb_x, x_lb, x_ub, x_box_sparsity, x_nom.back()); + lqocProblem2->setTerminalBoxConstraints(nb_x, x_lb, x_ub, x_box_sparsity, x_nom.back()); // check that constraint configuration is right ASSERT_TRUE(lqocProblem1->isConstrained()); ASSERT_FALSE(lqocProblem1->isGeneralConstrained()); - ASSERT_TRUE(lqocProblem1->isBoxConstrained()); + ASSERT_TRUE(lqocProblem1->isStateBoxConstrained()); + ASSERT_FALSE(lqocProblem1->isInputBoxConstrained()); // set and try to solve the problem for both solvers - hpipmSolver->configureBoxConstraints(lqocProblem1); + hpipmSolver->configureStateBoxConstraints(lqocProblem1); hpipmSolver->setProblem(lqocProblem1); hpipmSolver->initializeAndAllocate(); hpipmSolver->solve(); + hpipmSolver->computeStatesAndControls(); + hpipmSolver->computeFeedbackMatrices(); + + try + { + hpipmSolver->compute_lv(); + ASSERT_TRUE(false); // should never reach to this point + } catch (std::exception& e) + { + std::cout << "HPIPMSolver failed with exception " << e.what() << std::endl; + ASSERT_TRUE(true); + } try { @@ -230,38 +258,46 @@ void boxConstraintsTest(ct::core::ControlVector u0, // initialize the optimal control problems for both solvers lqocProblem1->setZero(); lqocProblem2->setZero(); - lqocProblem1->setFromTimeInvariantLinearQuadraticProblem(x0, u0, discreteExampleSystem, *costFunction, xf, dt); - lqocProblem2->setFromTimeInvariantLinearQuadraticProblem(x0, u0, discreteExampleSystem, *costFunction, xf, dt); + lqocProblem1->setFromTimeInvariantLinearQuadraticProblem(discreteExampleSystem, *costFunction, x0, dt); + lqocProblem2->setFromTimeInvariantLinearQuadraticProblem(discreteExampleSystem, *costFunction, x0, dt); // relax box constraints a bit for this test, otherwise there might be no solution x_lb.array() -= 1.0; x_ub.array() += 1.0; - // combine the box constraints manually for this test - int nb_ux = nb_x + nb_u; - Eigen::VectorXd ux_lb(nb_ux); - ux_lb << u_lb, x_lb; - Eigen::VectorXd ux_ub(nb_ux); - ux_ub << u_ub, x_ub; - Eigen::VectorXi ux_box_sparsity(nb_ux); - ux_box_sparsity << u_box_sparsity, x_box_sparsity; // set the combined box constraints - lqocProblem1->setIntermediateBoxConstraints(nb_ux, ux_lb, ux_ub, ux_box_sparsity); - lqocProblem2->setIntermediateBoxConstraints(nb_ux, ux_lb, ux_ub, ux_box_sparsity); - lqocProblem1->setTerminalBoxConstraints(nb_x, x_lb, x_ub, x_box_sparsity_terminal); - lqocProblem2->setTerminalBoxConstraints(nb_x, x_lb, x_ub, x_box_sparsity_terminal); + lqocProblem1->setInputBoxConstraints(nb_u, u_lb, u_ub, u_box_sparsity, u_nom); + lqocProblem2->setInputBoxConstraints(nb_u, u_lb, u_ub, u_box_sparsity, u_nom); + lqocProblem1->setIntermediateStateBoxConstraints(nb_x, x_lb, x_ub, x_box_sparsity, x_nom); + lqocProblem2->setIntermediateStateBoxConstraints(nb_x, x_lb, x_ub, x_box_sparsity, x_nom); + lqocProblem1->setTerminalBoxConstraints(nb_x, x_lb, x_ub, x_box_sparsity, x_nom.back()); + lqocProblem2->setTerminalBoxConstraints(nb_x, x_lb, x_ub, x_box_sparsity, x_nom.back()); // check that constraint configuration is right ASSERT_TRUE(lqocProblem1->isConstrained()); ASSERT_FALSE(lqocProblem1->isGeneralConstrained()); - ASSERT_TRUE(lqocProblem1->isBoxConstrained()); + ASSERT_TRUE(lqocProblem1->isInputBoxConstrained()); + ASSERT_TRUE(lqocProblem1->isStateBoxConstrained()); // set and try to solve the problem for both solvers - hpipmSolver->configureBoxConstraints(lqocProblem1); + hpipmSolver->configureInputBoxConstraints(lqocProblem1); + hpipmSolver->configureStateBoxConstraints(lqocProblem1); hpipmSolver->setProblem(lqocProblem1); hpipmSolver->initializeAndAllocate(); hpipmSolver->solve(); + hpipmSolver->computeStatesAndControls(); + hpipmSolver->computeFeedbackMatrices(); + + try + { + hpipmSolver->compute_lv(); + ASSERT_TRUE(false); // should never reach to this point + } catch (std::exception& e) + { + std::cout << "HPIPMSolver failed with exception " << e.what() << std::endl; + ASSERT_TRUE(true); + } try { @@ -343,21 +379,33 @@ void generalConstraintsTest(ct::core::ControlVector u0, } // initialize the optimal control problems for both solvers - lqocProblem1->setFromTimeInvariantLinearQuadraticProblem(x0, u0, discreteExampleSystem, *costFunction, xf, dt); - lqocProblem2->setFromTimeInvariantLinearQuadraticProblem(x0, u0, discreteExampleSystem, *costFunction, xf, dt); + lqocProblem1->setFromTimeInvariantLinearQuadraticProblem(discreteExampleSystem, *costFunction, x0, dt); + lqocProblem2->setFromTimeInvariantLinearQuadraticProblem(discreteExampleSystem, *costFunction, x0, dt); lqocProblem1->setGeneralConstraints(d_lb, d_ub, C, D); lqocProblem2->setGeneralConstraints(d_lb, d_ub, C, D); // check that constraint configuration is right ASSERT_TRUE(lqocProblem1->isConstrained()); ASSERT_TRUE(lqocProblem1->isGeneralConstrained()); - ASSERT_FALSE(lqocProblem1->isBoxConstrained()); + ASSERT_FALSE(lqocProblem1->isInputBoxConstrained()); + ASSERT_FALSE(lqocProblem1->isStateBoxConstrained()); // set and try to solve the problem for both solvers - hpipmSolver->configureBoxConstraints(lqocProblem1); hpipmSolver->setProblem(lqocProblem1); hpipmSolver->initializeAndAllocate(); hpipmSolver->solve(); + hpipmSolver->computeStatesAndControls(); + hpipmSolver->computeFeedbackMatrices(); + + try + { + hpipmSolver->compute_lv(); + ASSERT_TRUE(false); // should never reach to this point + } catch (std::exception& e) + { + std::cout << "HPIPMSolver failed with exception " << e.what() << std::endl; + ASSERT_TRUE(true); + } try { @@ -391,11 +439,11 @@ TEST(ConstrainedLQOCSolverTest, BoxConstrTest_small) // initial state ct::core::StateVector x0; - x0 << 2.5, 0.0; + x0 << 0.0, 0.0; // desired final state ct::core::StateVector xf; - xf.setConstant(0.0); + xf.setConstant(2.5); // dense control box constraints int nb_u = control_dim; @@ -410,15 +458,13 @@ TEST(ConstrainedLQOCSolverTest, BoxConstrTest_small) int nb_x = 1; Eigen::VectorXd x_lb(nb_x); Eigen::VectorXd x_ub(nb_x); - x_lb << 1.7; - x_ub.setConstant(std::numeric_limits::max()); + x_lb << -100; + x_ub.setConstant(1.7); Eigen::VectorXi x_box_sparsity(nb_x); - x_box_sparsity << 1; - Eigen::VectorXi x_box_sparsity_terminal(nb_x); - x_box_sparsity_terminal << 0; + x_box_sparsity << 0; boxConstraintsTest( - u0, x0, xf, nb_u, u_lb, u_ub, u_box_sparsity, nb_x, x_lb, x_ub, x_box_sparsity, x_box_sparsity_terminal); + u0, x0, xf, nb_u, u_lb, u_ub, u_box_sparsity, nb_x, x_lb, x_ub, x_box_sparsity); } TEST(ConstrainedLQOCSolverTest, BoxConstrTest_medium) @@ -428,15 +474,15 @@ TEST(ConstrainedLQOCSolverTest, BoxConstrTest_medium) // nominal control ct::core::ControlVector u0; - u0.setConstant(0.1); + u0.setConstant(0.0); // initial state ct::core::StateVector x0; - x0 << 2.5, 2.5, 0, 0, 0, 0, 0, 0; + x0 << 0, 0, 0, 0, 0, 0, 0, 0; // must start at 0 // desired final state ct::core::StateVector xf; - xf.setConstant(0.1); + xf << 2.5, 2.5, 0, 0, 0, 0, 0, 0; // dense control box constraints int nb_u = control_dim; @@ -451,15 +497,13 @@ TEST(ConstrainedLQOCSolverTest, BoxConstrTest_medium) int nb_x = 2; Eigen::VectorXd x_lb(nb_x); Eigen::VectorXd x_ub(nb_x); - x_lb << 1.5, 1.5; - x_ub.setConstant(std::numeric_limits::max()); + x_lb << -100, -100; + x_ub.setConstant(1.5); Eigen::VectorXi x_box_sparsity(nb_x); - x_box_sparsity << 3, 4; - Eigen::VectorXi x_box_sparsity_terminal(nb_x); - x_box_sparsity_terminal << 0, 1; + x_box_sparsity << 0, 1; boxConstraintsTest( - u0, x0, xf, nb_u, u_lb, u_ub, u_box_sparsity, nb_x, x_lb, x_ub, x_box_sparsity, x_box_sparsity_terminal); + u0, x0, xf, nb_u, u_lb, u_ub, u_box_sparsity, nb_x, x_lb, x_ub, x_box_sparsity); } TEST(ConstrainedLQOCSolverTest, GeneralConstrTest_small) @@ -473,11 +517,11 @@ TEST(ConstrainedLQOCSolverTest, GeneralConstrTest_small) // initial state ct::core::StateVector x0; - x0 << 2.5, 0.0; + x0 << 0.0, 0.0; // desired final state ct::core::StateVector xf; - xf.setConstant(0.0); + xf.setConstant(2.5); // general constraints // this general constraints is again nothing but an input inequality constraint: @@ -507,11 +551,11 @@ TEST(ConstrainedLQOCSolverTest, GeneralConstrTest_medium) // initial state ct::core::StateVector x0; - x0 << 2.5, 2.5, 0, 0, 0, 0, 0, 0; + x0 << 0.0, 0.0, 0, 0, 0, 0, 0, 0; // desired final state ct::core::StateVector xf; - xf.setConstant(0.1); + xf.setConstant(1.0); // general constraints // this general constraints is again nothing but an input inequality constraint: @@ -542,11 +586,11 @@ TEST(ConstrainedLQOCSolverTest, BoxConstraintUsingConstraintToolbox) // initial state ct::core::StateVector x0; - x0 << 2.5, 2.5, 0, 0, 0, 0, 0, 0; + x0 << 0.0, 0.0, 0, 0, 0, 0, 0, 0; // desired final state ct::core::StateVector xf; - xf.setConstant(0.1); + xf.setConstant(1.0); // input box constraint boundaries with sparsities in constraint toolbox format Eigen::VectorXi sp_control(control_dim); @@ -560,7 +604,7 @@ TEST(ConstrainedLQOCSolverTest, BoxConstraintUsingConstraintToolbox) Eigen::VectorXi sp_state(state_dim); sp_state << 1, 1, 0, 0, 0, 0, 0, 0; // note the different way of specifying sparsity Eigen::VectorXd x_lb(2); - x_lb << 0.5, 0.5; + x_lb << -0.5, -0.5; Eigen::VectorXd x_ub(2); x_ub.setConstant(std::numeric_limits::max()); @@ -574,14 +618,18 @@ TEST(ConstrainedLQOCSolverTest, BoxConstraintUsingConstraintToolbox) stateConstraint->setName("StateConstraint"); // create constraint container - std::shared_ptr> constraints( + std::shared_ptr> input_constraints( + new ct::optcon::ConstraintContainerAnalytical()); + + std::shared_ptr> state_constraints( new ct::optcon::ConstraintContainerAnalytical()); // add and initialize constraint terms - constraints->addIntermediateConstraint(controlConstraint, verbose); - constraints->addIntermediateConstraint(stateConstraint, verbose); - constraints->addTerminalConstraint(stateConstraint, verbose); - constraints->initialize(); + input_constraints->addIntermediateConstraint(controlConstraint, verbose); + state_constraints->addIntermediateConstraint(stateConstraint, verbose); + state_constraints->addTerminalConstraint(stateConstraint, verbose); + input_constraints->initialize(); + state_constraints->initialize(); //set up lqoc problems and solvers const size_t N = 5; @@ -621,6 +669,9 @@ TEST(ConstrainedLQOCSolverTest, BoxConstraintUsingConstraintToolbox) ct::core::ControlVectorArray uSol_hpipm; ct::core::FeedbackArray KSol_hpipm; + ct::core::StateVectorArray x_nom(N, x0); + ct::core::ControlVectorArray u_nom(N - 1, u0); + if (verbose) { std::cout << " ================================================== " << std::endl; @@ -630,53 +681,69 @@ TEST(ConstrainedLQOCSolverTest, BoxConstraintUsingConstraintToolbox) // initialize the optimal control problems for both solvers lqocProblem1->setZero(); - lqocProblem1->setFromTimeInvariantLinearQuadraticProblem(x0, u0, discreteExampleSystem, *costFunction, xf, dt); + lqocProblem1->setFromTimeInvariantLinearQuadraticProblem(discreteExampleSystem, *costFunction, x0, dt); // evaluate relevant quantities using the constraint toolbox - int nb_ux_intermediate = constraints->getJacobianStateNonZeroCountIntermediate() + - constraints->getJacobianInputNonZeroCountIntermediate(); - ASSERT_EQ(nb_ux_intermediate, 5); - int nb_x_terminal = constraints->getJacobianStateNonZeroCountTerminal(); + int nb_u_intermediate = input_constraints->getJacobianStateNonZeroCountIntermediate() + + input_constraints->getJacobianInputNonZeroCountIntermediate(); + int nb_x_intermediate = state_constraints->getJacobianStateNonZeroCountIntermediate() + + state_constraints->getJacobianInputNonZeroCountIntermediate(); + ASSERT_EQ(nb_u_intermediate + nb_x_intermediate, 5); + int nb_x_terminal = state_constraints->getJacobianStateNonZeroCountTerminal(); ASSERT_EQ(nb_x_terminal, 2); // get bounds - Eigen::VectorXd ux_lb_intermediate = constraints->getLowerBoundsIntermediate(); - Eigen::VectorXd ux_ub_intermediate = constraints->getUpperBoundsIntermediate(); - Eigen::VectorXd ux_lb_terminal = constraints->getLowerBoundsTerminal(); - Eigen::VectorXd ux_ub_terminal = constraints->getUpperBoundsTerminal(); + Eigen::VectorXd u_lb_intermediate = input_constraints->getLowerBoundsIntermediate(); + Eigen::VectorXd u_ub_intermediate = input_constraints->getUpperBoundsIntermediate(); + Eigen::VectorXd x_lb_intermediate = state_constraints->getLowerBoundsIntermediate(); + Eigen::VectorXd x_ub_intermediate = state_constraints->getUpperBoundsIntermediate(); + Eigen::VectorXd x_lb_terminal = state_constraints->getLowerBoundsTerminal(); + Eigen::VectorXd x_ub_terminal = state_constraints->getUpperBoundsTerminal(); // compute sparsity as required by LQOC Solver Eigen::VectorXi foo, u_sparsity_intermediate, x_sparsity_intermediate, x_sparsity_terminal; - constraints->sparsityPatternInputIntermediate(foo, u_sparsity_intermediate); - constraints->sparsityPatternStateIntermediate(foo, x_sparsity_intermediate); - Eigen::VectorXi ux_sparsity_intermediate(nb_ux_intermediate); - x_sparsity_intermediate.array() += control_dim; // shift indices to match combined decision vector [u, x] - ux_sparsity_intermediate << u_sparsity_intermediate, x_sparsity_intermediate; - - if (verbose) - std::cout << "ux_sparsity_intermediate" << ux_sparsity_intermediate.transpose() << std::endl; - - constraints->sparsityPatternStateTerminal(foo, x_sparsity_terminal); + input_constraints->sparsityPatternInputIntermediate(foo, u_sparsity_intermediate); + state_constraints->sparsityPatternStateIntermediate(foo, x_sparsity_intermediate); + state_constraints->sparsityPatternStateTerminal(foo, x_sparsity_terminal); if (verbose) + { + std::cout << "u_sparsity_intermediate" << u_sparsity_intermediate.transpose() << std::endl; + std::cout << "x_sparsity_intermediate" << x_sparsity_intermediate.transpose() << std::endl; std::cout << "x_sparsity_terminal" << x_sparsity_terminal.transpose() << std::endl; + } // set the combined box constraints to the LQOC problem - lqocProblem1->setIntermediateBoxConstraints( - nb_ux_intermediate, ux_lb_intermediate, ux_ub_intermediate, ux_sparsity_intermediate); - lqocProblem1->setTerminalBoxConstraints(nb_x_terminal, ux_lb_terminal, ux_ub_terminal, x_sparsity_terminal); + lqocProblem1->setInputBoxConstraints( + nb_u_intermediate, u_lb_intermediate, u_ub_intermediate, u_sparsity_intermediate, u_nom); + lqocProblem1->setIntermediateStateBoxConstraints( + nb_x_intermediate, x_lb_intermediate, x_ub_intermediate, x_sparsity_intermediate, x_nom); + lqocProblem1->setTerminalBoxConstraints( + nb_x_terminal, x_lb_terminal, x_ub_terminal, x_sparsity_terminal, x_nom.back()); // check that constraint configuration is right ASSERT_TRUE(lqocProblem1->isConstrained()); ASSERT_FALSE(lqocProblem1->isGeneralConstrained()); - ASSERT_TRUE(lqocProblem1->isBoxConstrained()); + ASSERT_TRUE(lqocProblem1->isInputBoxConstrained()); + ASSERT_TRUE(lqocProblem1->isStateBoxConstrained()); // set and try to solve the problem for both solvers - hpipmSolver->configureBoxConstraints(lqocProblem1); + hpipmSolver->configureInputBoxConstraints(lqocProblem1); + hpipmSolver->configureStateBoxConstraints(lqocProblem1); hpipmSolver->setProblem(lqocProblem1); hpipmSolver->initializeAndAllocate(); hpipmSolver->solve(); - + hpipmSolver->computeStatesAndControls(); + hpipmSolver->computeFeedbackMatrices(); + try + { + hpipmSolver->compute_lv(); + ASSERT_TRUE(false); // should never reach to this point + } catch (std::exception& e) + { + std::cout << "HPIPMSolver failed with exception " << e.what() << std::endl; + ASSERT_TRUE(true); + } // retrieve solutions from hpipm xSol_hpipm = hpipmSolver->getSolutionState(); diff --git a/ct_optcon/test/solver/linear/HPIPMInterfaceTest.h b/ct_optcon/test/solver/linear/HPIPMInterfaceTest.h index 1c75fbc49..685d5a746 100644 --- a/ct_optcon/test/solver/linear/HPIPMInterfaceTest.h +++ b/ct_optcon/test/solver/linear/HPIPMInterfaceTest.h @@ -27,7 +27,7 @@ TEST(HPIPMInterfaceTest, compareSolvers) // define an initial state StateVector x0; - x0 << 2.5, 2.5, 0, 0, 0, 0, 0, 0; + x0.setZero(); // by definition // define a desired terminal state StateVector stateOffset; @@ -35,7 +35,7 @@ TEST(HPIPMInterfaceTest, compareSolvers) // define a nominal control ControlVector u0; - u0.setConstant(-0.1); + u0.setZero(); // by definition // define cost function matrices StateMatrix Q; @@ -55,27 +55,35 @@ TEST(HPIPMInterfaceTest, compareSolvers) dt, system, ct::optcon::NLOptConSettings::APPROXIMATION::MATRIX_EXPONENTIAL); // initialize the linear quadratic optimal control problems - lqocProblem_hpipm->setFromTimeInvariantLinearQuadraticProblem( - x0, u0, discretizedSystem, costFunction, stateOffset, dt); - lqocProblem_gnriccati->setFromTimeInvariantLinearQuadraticProblem( - x0, u0, discretizedSystem, costFunction, stateOffset, dt); + lqocProblem_hpipm->setFromTimeInvariantLinearQuadraticProblem(discretizedSystem, costFunction, stateOffset, dt); + lqocProblem_gnriccati->setFromTimeInvariantLinearQuadraticProblem(discretizedSystem, costFunction, stateOffset, dt); // create hpipm solver instance, set and solve problem ct::optcon::HPIPMInterface hpipm; hpipm.setProblem(lqocProblem_hpipm); hpipm.solve(); + hpipm.computeStatesAndControls(); + hpipm.computeFeedbackMatrices(); + hpipm.compute_lv(); // create GNRiccati solver instance, set and solve problem ct::optcon::GNRiccatiSolver gnriccati; gnriccati.setProblem(lqocProblem_gnriccati); gnriccati.solve(); + gnriccati.computeStatesAndControls(); + gnriccati.computeFeedbackMatrices(); + gnriccati.compute_lv(); - // retrieve solutions + // compute and retrieve solutions ct::core::StateVectorArray x_sol_hpipm = hpipm.getSolutionState(); ct::core::StateVectorArray x_sol_gnrccati = gnriccati.getSolutionState(); ct::core::ControlVectorArray u_sol_hpipm = hpipm.getSolutionControl(); ct::core::ControlVectorArray u_sol_gnrccati = gnriccati.getSolutionControl(); + ct::core::FeedbackArray K_sol_hpipm = hpipm.getSolutionFeedback(); + ct::core::FeedbackArray K_sol_gnriccati = gnriccati.getSolutionFeedback(); + ct::core::ControlVectorArray lv_sol_hpipm = hpipm.get_lv(); + ct::core::ControlVectorArray lv_sol_gnriccati = gnriccati.get_lv(); // asser that the solution sizes the same ASSERT_EQ(x_sol_hpipm.size(), x_sol_gnrccati.size()); @@ -92,4 +100,16 @@ TEST(HPIPMInterfaceTest, compareSolvers) { ASSERT_LT((u_sol_hpipm[i] - u_sol_gnrccati[i]).array().abs().maxCoeff(), 1e-6); } + + // assert that feedback matrices are the same + for (size_t i = 0; i < K_sol_hpipm.size(); i++) + { + ASSERT_LT((K_sol_hpipm[i] - K_sol_gnriccati[i]).array().abs().maxCoeff(), 1e-6); + } + + // assert that feedforward-increment is the same + for (size_t i = 0; i < lv_sol_hpipm.size(); i++) + { + ASSERT_LT((lv_sol_hpipm[i] - lv_sol_gnriccati[i]).array().abs().maxCoeff(), 1e-6); + } } diff --git a/ct_optcon/test/solver/linear/LQOCSolverTest.cpp b/ct_optcon/test/solver/linear/LQOCSolverTest.cpp index 7f36717c4..6e4505f34 100644 --- a/ct_optcon/test/solver/linear/LQOCSolverTest.cpp +++ b/ct_optcon/test/solver/linear/LQOCSolverTest.cpp @@ -6,7 +6,7 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #include #include -// several tests which compare HPIPM and GNRiccati +// several tests which compare HPIPM and GNRiccati #include "LQOCSolverTest.h" #include "HPIPMInterfaceTest.h" diff --git a/ct_optcon/test/solver/linear/LQOCSolverTest.h b/ct_optcon/test/solver/linear/LQOCSolverTest.h index a173ca5da..57d204d8f 100644 --- a/ct_optcon/test/solver/linear/LQOCSolverTest.h +++ b/ct_optcon/test/solver/linear/LQOCSolverTest.h @@ -44,10 +44,10 @@ TEST(LQOCSolverTest, compareHPIPMandRiccati) // nominal control ct::core::ControlVector u0; - u0 << 0.1; + u0.setZero(); // by definition // initial state ct::core::StateVector x0; - x0 << 0.2, 0.1; + x0.setZero(); // by definition // desired final state ct::core::StateVector xf; xf << -1, 0; @@ -59,8 +59,8 @@ TEST(LQOCSolverTest, compareHPIPMandRiccati) b << 0.1, 0.1; // initialize the optimal control problems for both solvers - problems[0]->setFromTimeInvariantLinearQuadraticProblem(x0, u0, discreteExampleSystem, *costFunction, b, dt); - problems[1]->setFromTimeInvariantLinearQuadraticProblem(x0, u0, discreteExampleSystem, *costFunction, b, dt); + problems[0]->setFromTimeInvariantLinearQuadraticProblem(discreteExampleSystem, *costFunction, b, dt); + problems[1]->setFromTimeInvariantLinearQuadraticProblem(discreteExampleSystem, *costFunction, b, dt); // set the problem pointers lqocSolvers[0]->setProblem(problems[0]); @@ -70,17 +70,28 @@ TEST(LQOCSolverTest, compareHPIPMandRiccati) lqocSolvers[0]->initializeAndAllocate(); lqocSolvers[1]->initializeAndAllocate(); - // solve the problems + // solve the problems... lqocSolvers[0]->solve(); lqocSolvers[1]->solve(); + // postprocess data + lqocSolvers[0]->computeStatesAndControls(); + lqocSolvers[0]->computeFeedbackMatrices(); + lqocSolvers[0]->compute_lv(); + lqocSolvers[1]->computeStatesAndControls(); + lqocSolvers[1]->computeFeedbackMatrices(); + lqocSolvers[1]->compute_lv(); + // retrieve solutions from both solvers auto xSol_riccati = lqocSolvers[0]->getSolutionState(); auto uSol_riccati = lqocSolvers[0]->getSolutionControl(); ct::core::FeedbackArray KSol_riccati = lqocSolvers[0]->getSolutionFeedback(); + ct::core::ControlVectorArray lv_sol_riccati = lqocSolvers[0]->get_lv(); auto xSol_hpipm = lqocSolvers[1]->getSolutionState(); auto uSol_hpipm = lqocSolvers[1]->getSolutionControl(); ct::core::FeedbackArray KSol_hpipm = lqocSolvers[1]->getSolutionFeedback(); + ct::core::ControlVectorArray lv_sol_hpipm = lqocSolvers[1]->get_lv(); + for (size_t j = 0; j < xSol_riccati.size(); j++) { @@ -120,4 +131,17 @@ TEST(LQOCSolverTest, compareHPIPMandRiccati) // assert that feedback trajectories are identical for both solvers ASSERT_NEAR((KSol_riccati[j] - KSol_hpipm[j]).array().abs().maxCoeff(), 0.0, 1e-6); } + + for (size_t j = 0; j < lv_sol_riccati.size(); j++) + { + if (verbose) + { + std::cout << "lv solution from riccati solver:" << std::endl; + std::cout << lv_sol_riccati[j] << std::endl << std::endl; + std::cout << "lv solution from hpipm solver:" << std::endl; + std::cout << lv_sol_hpipm[j] << std::endl << std::endl; + } + // assert that feedforward increments are identical for both solvers + ASSERT_NEAR((lv_sol_riccati[j] - lv_sol_hpipm[j]).array().abs().maxCoeff(), 0.0, 1e-6); + } } diff --git a/ct_optcon/test/solver/linear/LQOCSolverTiming.cpp b/ct_optcon/test/solver/linear/LQOCSolverTiming.cpp index 4c5b6879f..6b1009df7 100644 --- a/ct_optcon/test/solver/linear/LQOCSolverTiming.cpp +++ b/ct_optcon/test/solver/linear/LQOCSolverTiming.cpp @@ -56,9 +56,9 @@ void timeSingleSolve(size_t N, std::vector>& loggedSolveTime dt, exampleSystem, core::SensitivityApproximationSettings::APPROXIMATION::MATRIX_EXPONENTIAL); ct::core::ControlVector u0; - u0.setRandom(); + u0.setZero(); ct::core::StateVector x0; - x0.setRandom(); + x0.setZero(); ct::core::StateVector xf; xf.setRandom(); @@ -80,8 +80,7 @@ void timeSingleSolve(size_t N, std::vector>& loggedSolveTime for (size_t j = 0; j < nRuns; j++) { - problems[i]->setFromTimeInvariantLinearQuadraticProblem( - x0, u0, discreteExampleSystem, *costFunction, b, dt); + problems[i]->setFromTimeInvariantLinearQuadraticProblem(discreteExampleSystem, *costFunction, b, dt); auto start_all = std::chrono::steady_clock::now(); @@ -95,6 +94,9 @@ void timeSingleSolve(size_t N, std::vector>& loggedSolveTime auto start_solve = std::chrono::steady_clock::now(); lqocSolvers[i]->solve(); + lqocSolvers[i]->computeStatesAndControls(); + lqocSolvers[i]->computeFeedbackMatrices(); + lqocSolvers[i]->compute_lv(); auto end_solve = std::chrono::steady_clock::now(); auto start_get = std::chrono::steady_clock::now(); diff --git a/ct_rbd/CMakeLists.txt b/ct_rbd/CMakeLists.txt index 1afb6d286..b69bf65ce 100644 --- a/ct_rbd/CMakeLists.txt +++ b/ct_rbd/CMakeLists.txt @@ -3,8 +3,9 @@ cmake_minimum_required (VERSION 3.3) include(${CMAKE_CURRENT_SOURCE_DIR}/../ct/cmake/compilerSettings.cmake) include(${CMAKE_CURRENT_SOURCE_DIR}/../ct/cmake/explicitTemplateHelpers.cmake) include(${CMAKE_CURRENT_SOURCE_DIR}/../ct/cmake/clang-cxx-dev-tools.cmake) +include(${CMAKE_CURRENT_SOURCE_DIR}/../ct/cmake/ct-cmake-helpers.cmake) -project(ct_rbd VERSION 3.0.1 LANGUAGES CXX) +project(ct_rbd VERSION 3.0.2 LANGUAGES CXX) set(CMAKE_MODULE_PATH "${CMAKE_SOURCE_DIR}/cmake") @@ -14,6 +15,10 @@ SET(CMAKE_EXPORT_COMPILE_COMMANDS TRUE) find_package(kindr REQUIRED) find_package(ct_optcon REQUIRED) +# extract interface compile definitions from ct_core and ct_optcon as options +importInterfaceCompileDefinitionsAsOptions(ct_core) +importInterfaceCompileDefinitionsAsOptions(ct_optcon) + ################### # BUILD LIBRARIES # diff --git a/ct_rbd/doc/ct_rbd.doxyfile b/ct_rbd/doc/ct_rbd.doxyfile index 1e1ce56fd..480b1d5be 100644 --- a/ct_rbd/doc/ct_rbd.doxyfile +++ b/ct_rbd/doc/ct_rbd.doxyfile @@ -38,13 +38,13 @@ PROJECT_NAME = "" # could be handy for archiving the generated documentation or if some version # control system is used. -PROJECT_NUMBER = 3.0.1 +PROJECT_NUMBER = 3.0.2 # Using the PROJECT_BRIEF tag one can provide an optional one line description # for a project that appears at the top of each page and should give viewer a # quick idea about the purpose of the project. Keep the description short. -PROJECT_BRIEF = " - 3.0.1 rigid body dynamics module." +PROJECT_BRIEF = " - 3.0.2 rigid body dynamics module." # With the PROJECT_LOGO tag one can specify an logo or icon that is included in diff --git a/ct_rbd/include/ct/rbd/nloc/FixBaseNLOC-impl.h b/ct_rbd/include/ct/rbd/nloc/FixBaseNLOC-impl.h index 583cd35f2..388dd7041 100644 --- a/ct_rbd/include/ct/rbd/nloc/FixBaseNLOC-impl.h +++ b/ct_rbd/include/ct/rbd/nloc/FixBaseNLOC-impl.h @@ -28,7 +28,8 @@ FixBaseNLOC::FixBaseNLOC( template FixBaseNLOC::FixBaseNLOC( std::shared_ptr> costFun, - std::shared_ptr> boxConstraints, + std::shared_ptr> inputBoxConstraints, + std::shared_ptr> stateBoxConstraints, std::shared_ptr> generalConstraints, const typename NLOptConSolver::Settings_t& nlocSettings, std::shared_ptr system, @@ -36,15 +37,17 @@ FixBaseNLOC::FixBaseNLOC( std::shared_ptr linearizedSystem) : system_(system), linearizedSystem_(linearizedSystem), - boxConstraints_(boxConstraints), + inputBoxConstraints_(inputBoxConstraints), + stateBoxConstraints_(stateBoxConstraints), generalConstraints_(generalConstraints), costFunction_(costFun), optConProblem_(system_, costFunction_, linearizedSystem_), iteration_(0) { - if (boxConstraints_ != nullptr) - optConProblem_.setBoxConstraints(boxConstraints_); - + if (inputBoxConstraints_ != nullptr) + optConProblem_.setInputBoxConstraints(inputBoxConstraints_); + if (stateBoxConstraints_ != nullptr) + optConProblem_.setStateBoxConstraints(stateBoxConstraints_); if (generalConstraints_ != nullptr) optConProblem_.setGeneralConstraints(generalConstraints_); diff --git a/ct_rbd/include/ct/rbd/nloc/FixBaseNLOC.h b/ct_rbd/include/ct/rbd/nloc/FixBaseNLOC.h index 955317d41..1a3abab1e 100644 --- a/ct_rbd/include/ct/rbd/nloc/FixBaseNLOC.h +++ b/ct_rbd/include/ct/rbd/nloc/FixBaseNLOC.h @@ -60,7 +60,8 @@ class FixBaseNLOC //! constructor which directly takes a cost function and constraints, mind the order of the constraints FixBaseNLOC(std::shared_ptr> costFun, - std::shared_ptr> boxConstraints, + std::shared_ptr> inputBoxConstraints, + std::shared_ptr> stateBoxConstraints, std::shared_ptr> generalConstraints, const typename NLOptConSolver::Settings_t& nlocSettings, std::shared_ptr system = std::shared_ptr(new FBSystem), @@ -120,7 +121,8 @@ class FixBaseNLOC std::shared_ptr system_; std::shared_ptr linearizedSystem_; std::shared_ptr costFunction_; - std::shared_ptr> boxConstraints_; + std::shared_ptr> inputBoxConstraints_; + std::shared_ptr> stateBoxConstraints_; std::shared_ptr> generalConstraints_; optcon::ContinuousOptConProblem optConProblem_; diff --git a/ct_rbd/include/ct/rbd/physics/EEContactModel.h b/ct_rbd/include/ct/rbd/physics/EEContactModel.h index 00eb164be..e5fb8989e 100644 --- a/ct_rbd/include/ct/rbd/physics/EEContactModel.h +++ b/ct_rbd/include/ct/rbd/physics/EEContactModel.h @@ -5,13 +5,15 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once -#include - #include +#pragma GCC diagnostic push // include IIT headers and disable warnings +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-value" #include #include #include +#pragma GCC diagnostic pop namespace ct { namespace rbd { @@ -173,6 +175,7 @@ class EEContactModel SCALAR& d() { return d_; } SCALAR& zOffset() { return zOffset_; } VELOCITY_SMOOTHING& smoothing() { return smoothing_; } + private: /** * \brief Checks if end-effector is in contact. Currently assumes this is the case for negative z @@ -291,5 +294,5 @@ class EEContactModel ActiveMap EEactive_; //!< stores which endeffectors are active, i.e. can make contact }; -} -} +} // namespace rbd +} // namespace ct diff --git a/ct_rbd/include/ct/rbd/robot/ProjectedDynamics.h b/ct_rbd/include/ct/rbd/robot/ProjectedDynamics.h index 671c70458..f8b6ec9ae 100644 --- a/ct_rbd/include/ct/rbd/robot/ProjectedDynamics.h +++ b/ct_rbd/include/ct/rbd/robot/ProjectedDynamics.h @@ -5,15 +5,15 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once -#include "jacobian/ConstraintJacobian.h" -#include "kinematics/RBDDataMap.h" -#include "Kinematics.h" -#include "state/JointAcceleration.h" -#include "state/RBDAcceleration.h" -#include "state/RBDState.h" -#include "state/RigidBodyAcceleration.h" -#include "state/RigidBodyPose.h" -#include "state/RigidBodyState.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include namespace ct { namespace rbd { diff --git a/ct_rbd/include/ct/rbd/robot/RobCoGenContainer.h b/ct_rbd/include/ct/rbd/robot/RobCoGenContainer.h index 397cb6569..441922e0a 100644 --- a/ct_rbd/include/ct/rbd/robot/RobCoGenContainer.h +++ b/ct_rbd/include/ct/rbd/robot/RobCoGenContainer.h @@ -5,7 +5,12 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-value" #include +#pragma GCC diagnostic pop + #include namespace ct { diff --git a/ct_rbd/include/ct/rbd/robot/costfunction/TermTaskspaceGeometricJacobian.hpp b/ct_rbd/include/ct/rbd/robot/costfunction/TermTaskspaceGeometricJacobian.hpp index f634e3908..3b9020187 100644 --- a/ct_rbd/include/ct/rbd/robot/costfunction/TermTaskspaceGeometricJacobian.hpp +++ b/ct_rbd/include/ct/rbd/robot/costfunction/TermTaskspaceGeometricJacobian.hpp @@ -41,7 +41,7 @@ class TermTaskspaceGeometricJacobian : public optcon::TermBase& w_pos_des, const Eigen::Quaterniond& w_q_des, const std::string& name = "TermTaskSpace") @@ -49,13 +49,12 @@ class TermTaskspaceGeometricJacobian : public optcon::TermBase& w_pos_des, const Eigen::Matrix3d& eulerXyz, const std::string& name = "TermTaskSpace") @@ -90,7 +89,7 @@ class TermTaskspaceGeometricJacobian : public optcon::TermBase::Zero()); - setup(); } //! construct this term with info loaded from a configuration file @@ -109,20 +107,25 @@ class TermTaskspaceGeometricJacobian : public optcon::TermBase* clone() const override { return new TermTaskspaceGeometricJacobian(*this); } - //! setup the AD Derivatives - void setup() {} //! evaluate virtual double evaluate(const Eigen::Matrix& x, const Eigen::Matrix& u, @@ -133,26 +136,25 @@ class TermTaskspaceGeometricJacobian : public optcon::TermBase(); // position difference in world frame - Eigen::Matrix xCurr = - kinematics_.getEEPositionInWorld(eeInd_, rbdState.basePose(), rbdState.jointPositions()).toImplementation(); + Eigen::Matrix xCurr = kinematics_.getEEPositionInWorld(eeInd_, rbdState.basePose(), rbdState.jointPositions()).toImplementation(); Eigen::Matrix xDiff = xCurr - x_ref_; // compute the cost from the position error - double pos_cost = (xDiff.transpose() * Q_pos_ * xDiff)(0, 0); + double pos_cost = 0.5 * (xDiff.transpose() * Q_pos_ * xDiff)(0, 0); // get current end-effector rotation in world frame Eigen::Matrix ee_rot = kinematics_.getEERotInBase(eeInd_, rbdState.jointPositions()); + Eigen::Quaterniond orientation(ee_rot); + Eigen::Quaterniond orientation_d_(R_ref_); + Eigen::Quaterniond error_quaternion(orientation * orientation_d_.inverse()); + // convert to axis angle + Eigen::AngleAxis error_quaternion_angle_axis(error_quaternion); + // compute "orientation position_error" + Eigen::Matrix qDiff = error_quaternion_angle_axis.axis() * error_quaternion_angle_axis.angle(); - // compute a measure for the difference between current rotation and desired rotation and compute cost based on the orientation error - // for the intuition behind, consider the following posts: - // https://math.stackexchange.com/a/87698 - // https://math.stackexchange.com/a/773635 - // Eigen::Matrix ee_R_diff = w_R_ref.transpose() * ee_rot; - - // compute rotation penalty using the squared Frobenius norm of (R_diff-I) - // double rot_cost = Q_rot_ * (ee_R_diff - Eigen::Matrix::Identity()).squaredNorm(); + double rot_cost = 0.5 * (qDiff.transpose() * Q_rot_ * qDiff)(0, 0); - return pos_cost; // + rot_cost; + return pos_cost + rot_cost; } @@ -165,19 +167,31 @@ class TermTaskspaceGeometricJacobian : public optcon::TermBase(); + rbdState.jointPositions() = x.template head(); + Eigen::Matrix J = kinematics_.getJacobianBaseEEbyId(eeInd_, rbdState); + Eigen::Matrix J_pos = J.template bottomRows<3>(); + Eigen::Matrix J_q = J.template topRows<3>(); + // position difference in world frame + Eigen::Matrix xCurr = + kinematics_.getEEPositionInWorld(eeInd_, rbdState.basePose(), rbdState.jointPositions()).toImplementation(); + Eigen::Matrix xDiff = xCurr - x_ref_; - grad.template head() = - 2 * Q_pos_ * - (kinematics_.getEEPositionInWorld(eeInd_, rbdState.basePose(), rbdState.jointPositions()) - .toImplementation() - - x_ref_) - .transpose() * - J; + grad.template head() += J_pos.transpose() * Q_pos_ * xDiff; - // todo implement !! + + // get current end-effector rotation in world frame + Eigen::Matrix ee_rot = kinematics_.getEERotInBase(eeInd_, rbdState.jointPositions()); + Eigen::Quaterniond orientation(ee_rot); + Eigen::Quaterniond orientation_d_(R_ref_); + Eigen::Quaterniond error_quaternion(orientation * orientation_d_.inverse()); + // convert to axis angle + Eigen::AngleAxis error_quaternion_angle_axis(error_quaternion); + // compute "orientation position_error" + Eigen::Matrix qDiff = error_quaternion_angle_axis.axis() * error_quaternion_angle_axis.angle(); + + grad.template head() += J_q.transpose() * Q_rot_ * qDiff; return grad; } @@ -195,7 +209,18 @@ class TermTaskspaceGeometricJacobian : public optcon::TermBase& u, const double& t) override { - throw std::runtime_error("stateSecondDerivative currently not defined for TermTaskspaceGeometricJacobian."); + RBDState rbdState; + rbdState.jointPositions() = x.template head(); + + Eigen::Matrix J = kinematics_.getJacobianBaseEEbyId(eeInd_, rbdState); + Eigen::Matrix J_pos = J.template bottomRows<3>(); + Eigen::Matrix J_q = J.template topRows<3>(); + + state_matrix_t Q = state_matrix_t::Zero(); + Q.template topLeftCorner() += J_pos.transpose() * Q_pos_ * J_pos; + Q.template topLeftCorner() += J_q.transpose() * Q_rot_ * J_q; + + return Q; } //! compute second order derivative of this cost term w.r.t. the control input @@ -222,7 +247,7 @@ class TermTaskspaceGeometricJacobian : public optcon::TermBase w_p_ref; @@ -257,9 +282,6 @@ class TermTaskspaceGeometricJacobian : public optcon::TermBase& w_R_ref) - { - R_ref_ = w_R_ref; - // // transcribe the rotation matrix into the parameter vector - // const Eigen::Matrix matVectorized( - // Eigen::Map>(w_R_ref.data(), 9)); - // adParameterVector_.template segment<9>(STATE_DIM + CONTROL_DIM + 3) = matVectorized; - } + void setReferenceOrientation(const Eigen::Matrix& w_R_ref) { R_ref_ = w_R_ref; } //! set desired end-effector orientation in world frame void setReferenceOrientation(const Eigen::Quaterniond& w_q_des) @@ -293,33 +308,6 @@ class TermTaskspaceGeometricJacobian : public optcon::TermBase - // const Eigen::Matrix extractReferenceRotationMatrix( - // const Eigen::Matrix& parameterVector) const - // { - // Eigen::Matrix matVectorized = parameterVector.template segment<9>(STATE_DIM + CONTROL_DIM + 3); - // Eigen::Matrix w_R_ee(Eigen::Map>(matVectorized.data(), 3, 3)); - // return w_R_ee; - // } - - // //! extract the state segment from the AD parameter vector - // template - // const Eigen::Matrix extractStateVector( - // const Eigen::Matrix& parameterVector) const - // { - // return parameterVector.template segment(0); - // } - // - // //! extract the control segment from the AD parameter vector - // template - // const Eigen::Matrix extractReferencePosition( - // const Eigen::Matrix& parameterVector) const - // { - // return parameterVector.template segment<3>(STATE_DIM + CONTROL_DIM); - // } - - //! index of the end-effector size_t eeInd_; @@ -329,8 +317,8 @@ class TermTaskspaceGeometricJacobian : public optcon::TermBase x_ref_; // ref position Eigen::Matrix R_ref_; // ref rotation diff --git a/ct_rbd/include/ct/rbd/robot/costfunction/TermTaskspacePose.hpp b/ct_rbd/include/ct/rbd/robot/costfunction/TermTaskspacePose.hpp index 5571fffb5..846648f52 100644 --- a/ct_rbd/include/ct/rbd/robot/costfunction/TermTaskspacePose.hpp +++ b/ct_rbd/include/ct/rbd/robot/costfunction/TermTaskspacePose.hpp @@ -5,6 +5,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once +#ifdef CPPADCG + #include #include @@ -280,3 +282,5 @@ class TermTaskspacePose : public optcon::TermBase #include @@ -492,3 +494,5 @@ class TermTaskspacePoseCG : public optcon::TermBase #include @@ -162,3 +164,5 @@ class TermTaskspacePosition : public optcon::TermBase +template class IKCostEvaluator final : public ct::optcon::tpl::DiscreteCostEvaluatorBase { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW - static const size_t NJOINTS = KINEMATICS_AD::NJOINTS; + static const size_t NJOINTS = KINEMATICS::NJOINTS; - IKCostEvaluator(size_t eeInd, const Eigen::Matrix3d& Qpos = Eigen::Matrix3d::Identity(), const double& Qrot = 1.0) + IKCostEvaluator(size_t eeInd, + const Eigen::Matrix3d& Qpos = Eigen::Matrix3d::Identity(), + const Eigen::Matrix3d& Qrot = Eigen::Matrix3d::Identity()) : w_(nullptr), - goalCostTerm_(new ct::rbd::TermTaskspacePoseCG(eeInd, Qpos, Qrot)), + goalCostTerm_(new ct::rbd::TermTaskspaceGeometricJacobian(eeInd, Qpos, Qrot)), jointRefTerm_(nullptr), ikRegularizer_(nullptr) { @@ -37,7 +39,7 @@ class IKCostEvaluator final : public ct::optcon::tpl::DiscreteCostEvaluatorBase< const std::string& termTaskspaceName, const bool verbose = false) : w_(nullptr), - goalCostTerm_(new ct::rbd::TermTaskspacePoseCG(costFunctionPath, + goalCostTerm_(new ct::rbd::TermTaskspaceGeometricJacobian(costFunctionPath, termTaskspaceName, verbose)), jointRefTerm_(nullptr), @@ -51,7 +53,7 @@ class IKCostEvaluator final : public ct::optcon::tpl::DiscreteCostEvaluatorBase< const std::string& termJointPosName, const bool verbose = false) : w_(nullptr), - goalCostTerm_(new ct::rbd::TermTaskspacePoseCG(costFunctionPath, + goalCostTerm_(new ct::rbd::TermTaskspaceGeometricJacobian(costFunctionPath, termTaskspaceName, verbose)), jointRefTerm_( @@ -64,9 +66,12 @@ class IKCostEvaluator final : public ct::optcon::tpl::DiscreteCostEvaluatorBase< //! opt vector needs to be set by NLP solver void setOptVector(std::shared_ptr> optVector) { w_ = optVector; } + // set an optional regularizer (if necessary) void setRegularizer(std::shared_ptr reg) { ikRegularizer_ = reg; } + ct::rbd::RigidBodyPose getTargetPose() { return goalCostTerm_->getReferencePose(); } + // set the target pose as rbd pose directly void setTargetPose(const ct::rbd::RigidBodyPose& rbdPose) { @@ -181,7 +186,7 @@ class IKCostEvaluator final : public ct::optcon::tpl::DiscreteCostEvaluatorBase< private: std::shared_ptr> w_; - std::shared_ptr> goalCostTerm_; + std::shared_ptr> goalCostTerm_; std::shared_ptr> jointRefTerm_; diff --git a/ct_rbd/include/ct/rbd/robot/kinematics/ik_nlp/IKNLPSolverIpopt.h b/ct_rbd/include/ct/rbd/robot/kinematics/ik_nlp/IKNLPSolverIpopt.h index 2900422f0..052290777 100644 --- a/ct_rbd/include/ct/rbd/robot/kinematics/ik_nlp/IKNLPSolverIpopt.h +++ b/ct_rbd/include/ct/rbd/robot/kinematics/ik_nlp/IKNLPSolverIpopt.h @@ -191,5 +191,5 @@ class IKNLPSolverIpopt : public ct::rbd::InverseKinematicsBase(); } + /// @brief get constant joint state const JointPositionBlockConst getPositions() const { return state_.template head(); } + SCALAR& getPosition(size_t i) { assert(i < NJOINTS && "Invalid joint index"); return state_(i); } + const SCALAR& getPosition(size_t i) const { assert(i < NJOINTS && "Invalid joint index"); @@ -98,7 +101,7 @@ class JointState int k_lower = std::floor((getPosition(i) - (lowerLimitVec[i] - tolerance)) / (2 * M_PI)); int k_upper = std::floor((getPosition(i) - (lowerLimitVec[i] + tolerance)) / (2 * M_PI)); - if (abs(k_lower) <= abs(k_upper)) + if (std::abs(k_lower) <= std::abs(k_upper)) { if (k_lower != 0) getPosition(i) -= k_lower * 2 * M_PI; @@ -114,43 +117,50 @@ class JointState { assert(lowerLimit.size() == NJOINTS && upperLimit.size() == NJOINTS && "Wrong limit dimensions"); for (size_t i = 0; i < NJOINTS; ++i) - if ((abs(getPosition(i) - lowerLimit[i]) > tolerance && getPosition(i) < lowerLimit[i]) || - (abs(getPosition(i) - upperLimit[i]) > tolerance && getPosition(i) > upperLimit[i])) + if ((std::abs(getPosition(i) - lowerLimit[i]) > tolerance && getPosition(i) < lowerLimit[i]) || + (std::abs(getPosition(i) - upperLimit[i]) > tolerance && getPosition(i) > upperLimit[i])) return false; return true; } /// @brief get joint velocity JointPositionBlock getVelocities() { return state_.template tail(); } + /// @brief get constant joint velocity const JointPositionBlockConst getVelocities() const { return state_.template tail(); } + SCALAR& getVelocity(size_t i) { assert(i < NJOINTS && "Invalid joint index"); return state_(NJOINTS + i); } + const SCALAR& getVelocity(size_t i) const { assert(i < NJOINTS && "Invalid joint index"); return state_(NJOINTS + i); } + /// @brief check joint velocity limits template bool checkVelocityLimits(T limit) { assert(limit.size() == NJOINTS && "Wrong limit dimension"); for (size_t i = 0; i < NJOINTS; ++i) - if (abs(getVelocity(i)) > limit[i]) + if (std::abs(getVelocity(i)) > limit[i]) return false; return true; } - joint_state_vector_t& toImplementation() { return state_; } + const joint_state_vector_t& toImplementation() const { return state_; } + /// @brief set states to zero void setZero() { state_.setZero(); } + void setRandom() { state_.setRandom(); } + protected: joint_state_vector_t state_; }; diff --git a/ct_rbd/include/ct/rbd/state/RigidBodyPose.h b/ct_rbd/include/ct/rbd/state/RigidBodyPose.h index 5dac7d1d9..eda608ad7 100644 --- a/ct_rbd/include/ct/rbd/state/RigidBodyPose.h +++ b/ct_rbd/include/ct/rbd/state/RigidBodyPose.h @@ -5,7 +5,11 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-value" #include +#pragma GCC diagnostic pop namespace ct { namespace rbd { @@ -100,11 +104,9 @@ class RigidBodyPose { } - //RigidBodyPose(const Eigen::Vector3d& orientationEulerXyz, const Eigen::Vector3d& position, STORAGE_TYPE storage = QUAT); - //RigidBodyPose(const Eigen::Quaterniond& orientationQuat, const Eigen::Vector3d& position, STORAGE_TYPE storage = QUAT); - //! destructor for a rigid body pose - ~RigidBodyPose() {} + ~RigidBodyPose() = default; + inline bool isNear(const RigidBodyPose& rhs, const double& tol = 1e-10) const { return getRotationQuaternion().isNear(rhs.getRotationQuaternion(), tol) && @@ -215,7 +217,7 @@ class RigidBodyPose { if (storedAsEuler()) { - euler_ = kindr::EulerAnglesXyz(quat); + euler_ = kindr::EulerAnglesXyz(kindr::RotationQuaternion(quat)); } else { @@ -241,13 +243,13 @@ class RigidBodyPose /** * \brief This method returns the position of the Base frame in the inertia frame. */ - const Position3Tpl& position() const { return position_; } + /** * \brief This method returns the position of the Base frame in the inertia frame. */ - Position3Tpl& position() { return position_; } + /** * \brief This method returns the Base frame in a custom Frame specified in the Inertia Frame. */ @@ -400,6 +402,7 @@ class RigidBodyPose } STORAGE_TYPE getStorageType() const { return storage_; } + private: bool storedAsEuler() const { diff --git a/ct_rbd/include/ct/rbd/systems/FixBaseSystemBase.h b/ct_rbd/include/ct/rbd/systems/FixBaseSystemBase.h index 96463e19d..fbdf53c06 100644 --- a/ct_rbd/include/ct/rbd/systems/FixBaseSystemBase.h +++ b/ct_rbd/include/ct/rbd/systems/FixBaseSystemBase.h @@ -58,7 +58,7 @@ class FixBaseSystemBase : public RBDSystem, virtual void computeControlledDynamics(const ct::core::StateVector& state, const SCALAR& t, const ct::core::ControlVector& controlIn, - ct::core::StateVector& derivative) = 0; + ct::core::StateVector& derivative) override = 0; //! deep cloning virtual FixBaseSystemBase* clone() const override = 0; diff --git a/ct_rbd/include/ct/rbd/systems/RBDSystem.h b/ct_rbd/include/ct/rbd/systems/RBDSystem.h index e05a9ed23..aaf02c4e9 100644 --- a/ct_rbd/include/ct/rbd/systems/RBDSystem.h +++ b/ct_rbd/include/ct/rbd/systems/RBDSystem.h @@ -3,8 +3,7 @@ This file is part of the Control Toolbox (https://github.com/ethz-adrl/control-t Licensed under the BSD-2 license (see LICENSE file in main directory) **********************************************************************************************************************/ -#ifndef INCLUDE_CT_RBD_SYSTEMS_RBDSYSTEM_H_ -#define INCLUDE_CT_RBD_SYSTEMS_RBDSYSTEM_H_ +#pragma once namespace ct { namespace rbd { @@ -16,15 +15,12 @@ template class RBDSystem { public: - RBDSystem() {} - virtual ~RBDSystem() {} + RBDSystem() = default; + virtual ~RBDSystem() = default; virtual RBDDynamics& dynamics() = 0; virtual const RBDDynamics& dynamics() const = 0; private: }; -} -} - - -#endif /* INCLUDE_CT_RBD_SYSTEMS_RBDSYSTEM_H_ */ +} // namespace rbd +} // namespace ct diff --git a/ct_rbd/include/ct/rbd/systems/linear/RbdLinearizer.h b/ct_rbd/include/ct/rbd/systems/linear/RbdLinearizer.h index 89c10dd3d..1ab3430eb 100644 --- a/ct_rbd/include/ct/rbd/systems/linear/RbdLinearizer.h +++ b/ct_rbd/include/ct/rbd/systems/linear/RbdLinearizer.h @@ -17,7 +17,11 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #include +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-value" #include +#pragma GCC diagnostic pop template struct print_size_as_warning @@ -98,8 +102,9 @@ class RbdLinearizer : public ct::core::SystemLinearizer eulerXyz(x.template topRows<3>()); kindr::RotationMatrix R_WB_kindr(eulerXyz); - Eigen::Matrix jacAngVel = jacobianOfAngularVelocityMapping(x.template topRows<3>(), - x.template segment<3>(STATE_DIM / 2)).transpose(); + Eigen::Matrix jacAngVel = + jacobianOfAngularVelocityMapping(x.template topRows<3>(), x.template segment<3>(STATE_DIM / 2)) + .transpose(); //this->dFdx_.template block<3,3>(0,0) = -R_WB_kindr.toImplementation() * JacobianOfRotationMultiplyVector( x.template topRows<3>(), R_WB_kindr.toImplementation()*(x.template segment<3>(STATE_DIM/2) )); this->dFdx_.template block<3, 3>(0, 0) = jacAngVel.template block<3, 3>(0, 0); @@ -278,5 +283,5 @@ class RbdLinearizer : public ct::core::SystemLinearizer ct_rbd - 3.0.1 + 3.0.2 Control toolbox - rbd module. diff --git a/ct_rbd/src/kindrEulerInverseRotateTest.cpp b/ct_rbd/src/kindrEulerInverseRotateTest.cpp index 1742ea3e9..36b80cb8d 100644 --- a/ct_rbd/src/kindrEulerInverseRotateTest.cpp +++ b/ct_rbd/src/kindrEulerInverseRotateTest.cpp @@ -5,7 +5,12 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #include + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-value" #include +#pragma GCC diagnostic pop int main() { diff --git a/ct_rbd/test/CMakeLists.txt b/ct_rbd/test/CMakeLists.txt index b4dc60c02..2f7908e26 100644 --- a/ct_rbd/test/CMakeLists.txt +++ b/ct_rbd/test/CMakeLists.txt @@ -33,7 +33,6 @@ package_add_test(FloatingBaseFDSystemTest systems/FloatingBaseFDSystemTest.cpp) package_add_test(FixBaseFDSystemTest systems/FixBaseFDSystemTest.cpp) -package_add_test(ProjectedFDSystemTest systems/ProjectedFDSystemTest.cpp) package_add_test(RBDLinearizerTest systems/linear/RBDLinearizerTest.cpp) @@ -41,15 +40,19 @@ package_add_test(EEKinematicsTest robot/kinematics/EEKinematicsTest.cpp) package_add_test(EEContactModelTest physics/EEContactModelTest.cpp) -package_add_test(TaskSpaceCfTest robot/costfunction/TaskspaceCostFunctionTest.cpp) - -package_add_test(rbdJITtests robot/costfunction/rbdJITtests.cpp) +package_add_test(jacobianTests robot/jacobian/JacobianTests.cpp) -package_add_test(kindrJITtest robot/costfunction/kindrJITtest.cpp) +if(CPPADCG) + message(STATUS "ct_rbd: building unit tests requiring CPPADCG") + package_add_test(ProjectedFDSystemTest systems/ProjectedFDSystemTest.cpp) + package_add_test(TaskSpaceCfTest robot/costfunction/TaskspaceCostFunctionTest.cpp) + package_add_test(rbdJITtests robot/costfunction/rbdJITtests.cpp) + package_add_test(kindrJITtest robot/costfunction/kindrJITtest.cpp) +endif() -package_add_test(jacobianTests robot/jacobian/JacobianTests.cpp) if(BUILD_WITH_IPOPT_SUPPORT) + message(STATUS "ct_rbd: building unit tests requiring IPOPT") package_add_test(FixBaseIKTest robot/kinematics/FixBaseIKTest.cpp) endif() diff --git a/ct_rbd/test/operationalSpace/OperationalSpaceTest.cpp b/ct_rbd/test/operationalSpace/OperationalSpaceTest.cpp index 68c6d9133..55144c1d7 100644 --- a/ct_rbd/test/operationalSpace/OperationalSpaceTest.cpp +++ b/ct_rbd/test/operationalSpace/OperationalSpaceTest.cpp @@ -3,6 +3,11 @@ This file is part of the Control Toolbox (https://github.com/ethz-adrl/control-t Licensed under the BSD-2 license (see LICENSE file in main directory) **********************************************************************************************************************/ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-value" + + #include #include @@ -88,3 +93,6 @@ int main(int argc, char** argv) testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } + + +#pragma GCC diagnostic pop diff --git a/ct_rbd/test/robot/costfunction/kindrJITtest.h b/ct_rbd/test/robot/costfunction/kindrJITtest.h index a31138d6c..4860a2a07 100644 --- a/ct_rbd/test/robot/costfunction/kindrJITtest.h +++ b/ct_rbd/test/robot/costfunction/kindrJITtest.h @@ -5,8 +5,11 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) #pragma once +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-value" #include - +#pragma GCC diagnostic pop /*! * A 3x3 function which constructs a a kindr EulerAngles object in between. diff --git a/ct_rbd/test/robot/jacobian/JacobianTests.cpp b/ct_rbd/test/robot/jacobian/JacobianTests.cpp index eb1006d1c..c6224967b 100644 --- a/ct_rbd/test/robot/jacobian/JacobianTests.cpp +++ b/ct_rbd/test/robot/jacobian/JacobianTests.cpp @@ -3,6 +3,11 @@ This file is part of the Control Toolbox (https://github.com/ethz-adrl/control-t Licensed under the BSD-2 license (see LICENSE file in main directory) **********************************************************************************************************************/ + +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-value" + #include #include #include "../../models/testhyq/RobCoGenTestHyQ.h" @@ -46,3 +51,6 @@ int main(int argc, char** argv) testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } + + + #pragma GCC diagnostic pop \ No newline at end of file diff --git a/ct_rbd/test/robot/kinematics/EEKinematicsTest.cpp b/ct_rbd/test/robot/kinematics/EEKinematicsTest.cpp index 2c6a9f8d0..c40c88c55 100644 --- a/ct_rbd/test/robot/kinematics/EEKinematicsTest.cpp +++ b/ct_rbd/test/robot/kinematics/EEKinematicsTest.cpp @@ -146,7 +146,9 @@ TEST(EEKinematicsTest, testFootPositionVaryingBase) // all legs should have same height if (i > 0) + { ASSERT_NEAR(B_eePos[0](2), B_eePos[i](2), 1e-6); + } // legs should be below belly ASSERT_LT(B_eePos[0](2), -0.5); @@ -183,7 +185,9 @@ TEST(EEKinematicsTest, testFootPositionStraightBase) // all legs should have same height if (i > 0) + { ASSERT_NEAR(W_eePos[0](2), W_eePos[i](2), 1e-6); + } // legs should be below belly ASSERT_LT(W_eePos[0](2), state.basePose().position()(2) - 0.5); @@ -232,7 +236,9 @@ TEST(EEKinematicsTest, forceMappingTest) for (size_t j = 0; j < 6; j++) { if (j != 3) + { ASSERT_NEAR(eeForceLink(j), 0.0, 1e-6); + } } ASSERT_NEAR(eeForceLink(3), -eeForcesW[i](5), 1e-6); diff --git a/ct_rbd/test/robot/kinematics/FixBaseIKTest.cpp b/ct_rbd/test/robot/kinematics/FixBaseIKTest.cpp index 0111b9ed6..4d981224b 100644 --- a/ct_rbd/test/robot/kinematics/FixBaseIKTest.cpp +++ b/ct_rbd/test/robot/kinematics/FixBaseIKTest.cpp @@ -11,9 +11,8 @@ Licensed under the BSD-2 license (see LICENSE file in main directory) const size_t njoints = ct::rbd::TestIrb4600::Kinematics::NJOINTS; -using KinematicsAD_t = ct::rbd::TestIrb4600::tpl::Kinematics; using Kinematics_t = ct::rbd::TestIrb4600::tpl::Kinematics; -using IKProblem = ct::rbd::IKNLP; +using IKProblem = ct::rbd::IKNLP; using IKNLPSolver = ct::rbd::IKNLPSolverIpopt; @@ -24,8 +23,8 @@ TEST(FixBaseInverseKinematicsTest, NLPIKTest) ct::rbd::JointState::Position jointLowerLimit = ct::rbd::TestIrb4600::jointLowerLimit(); ct::rbd::JointState::Position jointUpperLimit = ct::rbd::TestIrb4600::jointUpperLimit(); - std::shared_ptr> ikCostEvaluator( - new ct::rbd::IKCostEvaluator(eeInd)); + std::shared_ptr> ikCostEvaluator( + new ct::rbd::IKCostEvaluator(eeInd)); std::shared_ptr ik_problem(new IKProblem(ikCostEvaluator, jointLowerLimit, jointUpperLimit)); @@ -39,6 +38,7 @@ TEST(FixBaseInverseKinematicsTest, NLPIKTest) ct::rbd::InverseKinematicsSettings ikSettings; ikSettings.maxNumTrials_ = 100; ikSettings.randomizeInitialGuess_ = true; + ikSettings.validationTol_ = 1e-6; IKNLPSolver ikSolver(ik_problem, nlpSolverSettings, ikSettings, eeInd); diff --git a/ct_rbd/test/robot/kinematics/KinematicsTest.cpp b/ct_rbd/test/robot/kinematics/KinematicsTest.cpp index 0644cf54f..d820ee737 100644 --- a/ct_rbd/test/robot/kinematics/KinematicsTest.cpp +++ b/ct_rbd/test/robot/kinematics/KinematicsTest.cpp @@ -3,6 +3,11 @@ This file is part of the Control Toolbox (https://github.com/ethz-adrl/control-t Licensed under the BSD-2 license (see LICENSE file in main directory) **********************************************************************************************************************/ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-value" +#pragma GCC diagnostic ignored "-Wunused-variable" + #include #include @@ -48,3 +53,5 @@ int main(int argc, char** argv) testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } + +#pragma GCC diagnostic pop diff --git a/ct_rbd/test/robot/kinematics/KinematicsTestAd.cpp b/ct_rbd/test/robot/kinematics/KinematicsTestAd.cpp index c53a3d8b6..2d1868a7d 100644 --- a/ct_rbd/test/robot/kinematics/KinematicsTestAd.cpp +++ b/ct_rbd/test/robot/kinematics/KinematicsTestAd.cpp @@ -3,6 +3,11 @@ This file is part of the Control Toolbox (https://github.com/ethz-adrl/control-t Licensed under the BSD-2 license (see LICENSE file in main directory) **********************************************************************************************************************/ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-value" +#pragma GCC diagnostic ignored "-Wunused-variable" + #include #include @@ -47,3 +52,5 @@ int main(int argc, char** argv) testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } + +#pragma GCC diagnostic pop diff --git a/ct_rbd/test/systems/FloatingBaseFDSystemTest.cpp b/ct_rbd/test/systems/FloatingBaseFDSystemTest.cpp index 3c73e2939..3bf0cbb64 100644 --- a/ct_rbd/test/systems/FloatingBaseFDSystemTest.cpp +++ b/ct_rbd/test/systems/FloatingBaseFDSystemTest.cpp @@ -3,6 +3,12 @@ This file is part of the Control Toolbox (https://github.com/ethz-adrl/control-t Licensed under the BSD-2 license (see LICENSE file in main directory) **********************************************************************************************************************/ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-value" +#pragma GCC diagnostic ignored "-Wunused-variable" + + #include #include @@ -51,3 +57,5 @@ int main(int argc, char** argv) testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } + +#pragma GCC diagnostic pop \ No newline at end of file diff --git a/ct_rbd/test/systems/ProjectedFDSystemTest.cpp b/ct_rbd/test/systems/ProjectedFDSystemTest.cpp index 2923d74d8..3d5767720 100644 --- a/ct_rbd/test/systems/ProjectedFDSystemTest.cpp +++ b/ct_rbd/test/systems/ProjectedFDSystemTest.cpp @@ -3,6 +3,12 @@ This file is part of the Control Toolbox (https://github.com/ethz-adrl/control-t Licensed under the BSD-2 license (see LICENSE file in main directory) **********************************************************************************************************************/ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-value" +#pragma GCC diagnostic ignored "-Wunused-variable" + + #include @@ -207,3 +213,7 @@ int main(int argc, char** argv) testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } + + +#pragma GCC diagnostic pop + diff --git a/ct_rbd/test/systems/linear/RBDLinearizerTest.cpp b/ct_rbd/test/systems/linear/RBDLinearizerTest.cpp index 3af138352..f745762b2 100644 --- a/ct_rbd/test/systems/linear/RBDLinearizerTest.cpp +++ b/ct_rbd/test/systems/linear/RBDLinearizerTest.cpp @@ -3,6 +3,11 @@ This file is part of the Control Toolbox (https://github.com/ethz-adrl/control-t Licensed under the BSD-2 license (see LICENSE file in main directory) **********************************************************************************************************************/ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wunused-value" +#pragma GCC diagnostic ignored "-Wunused-variable" + #include #include @@ -112,3 +117,6 @@ int main(int argc, char** argv) testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } + + +#pragma GCC diagnostic pop \ No newline at end of file